2 Commits

Author SHA1 Message Date
f90994961b Added basic launch file for mg_lidar 2025-05-06 15:27:07 +02:00
a4660d4a3b Added lidar opponent tracking 2025-05-06 03:09:12 +02:00
37 changed files with 25 additions and 459 deletions

84
flake.lock generated
View File

@ -1,84 +0,0 @@
{
"nodes": {
"flake-utils": {
"inputs": {
"systems": "systems"
},
"locked": {
"lastModified": 1731533236,
"narHash": "sha256-l0KFg5HjrsfsO/JpG+r7fRrqm12kzFHyUHqHCVpMMbI=",
"owner": "numtide",
"repo": "flake-utils",
"rev": "11707dc2f618dd54ca8739b309ec4fc024de578b",
"type": "github"
},
"original": {
"owner": "numtide",
"repo": "flake-utils",
"type": "github"
}
},
"nix-ros-overlay": {
"inputs": {
"flake-utils": "flake-utils",
"nixpkgs": "nixpkgs"
},
"locked": {
"lastModified": 1761810010,
"narHash": "sha256-o0wJKW603SiOO373BTgeZaF6nDxegMA/cRrzSC2Cscg=",
"owner": "lopsided98",
"repo": "nix-ros-overlay",
"rev": "e277df39e3bc6b372a5138c0bcf10198857c55ab",
"type": "github"
},
"original": {
"owner": "lopsided98",
"ref": "master",
"repo": "nix-ros-overlay",
"type": "github"
}
},
"nixpkgs": {
"locked": {
"lastModified": 1744849697,
"narHash": "sha256-S9hqvanPSeRu6R4cw0OhvH1rJ+4/s9xIban9C4ocM/0=",
"owner": "lopsided98",
"repo": "nixpkgs",
"rev": "6318f538166fef9f5118d8d78b9b43a04bb049e4",
"type": "github"
},
"original": {
"owner": "lopsided98",
"ref": "nix-ros",
"repo": "nixpkgs",
"type": "github"
}
},
"root": {
"inputs": {
"nix-ros-overlay": "nix-ros-overlay",
"nixpkgs": [
"nix-ros-overlay",
"nixpkgs"
]
}
},
"systems": {
"locked": {
"lastModified": 1681028828,
"narHash": "sha256-Vy1rq5AaRuLzOxct8nz4T6wlgyUR7zLU309k9mBC768=",
"owner": "nix-systems",
"repo": "default",
"rev": "da67096a3b9bf56a91d16901293e51ba5b49a27e",
"type": "github"
},
"original": {
"owner": "nix-systems",
"repo": "default",
"type": "github"
}
}
},
"root": "root",
"version": 7
}

View File

@ -1,76 +0,0 @@
{
inputs = {
nix-ros-overlay.url = "github:lopsided98/nix-ros-overlay/master";
nixpkgs.follows = "nix-ros-overlay/nixpkgs";
};
outputs =
{
self,
nix-ros-overlay,
nixpkgs,
}:
nix-ros-overlay.inputs.flake-utils.lib.eachDefaultSystem (
system:
let
pkgs = import nixpkgs {
inherit system;
overlays = [ nix-ros-overlay.overlays.default ];
};
in
{
devShells.default = pkgs.mkShell {
name = "Project Robotoid";
packages = [
pkgs.colcon
pkgs.llvmPackages_20.clang-tools
(
with pkgs.rosPackages.jazzy;
buildEnv {
paths = [
# Dependencies from package.xml files
desktop
ament-cmake-core
python-cmake-module
ament-lint-auto
ament-lint-common
behaviortree-cpp
controller-manager
diff-drive-controller
geometry-msgs
hardware-interface
joint-state-broadcaster
launch
launch-ros
pkgs.glm
pkgs.jsoncpp.dev
pkgs.i2c-tools
pluginlib
rclcpp
rclcpp-action
rclcpp-components
rclcpp-lifecycle
robot-state-publisher
ros2-control
ros2launch
rosidl-default-generators
rosidl-default-runtime
sensor-msgs
std-msgs
std-srvs
tf2
tf2-geometry-msgs
tf2-ros
visualization-msgs
];
}
)
];
};
}
);
nixConfig = {
extra-substituters = [ "https://attic.iid.ciirc.cvut.cz/ros" ];
extra-trusted-public-keys = [ "ros.cachix.org-1:dSyZxI8geDCJrwgvCOHDoAfOm5sV1wCPjBkKL+38Rvo=" ];
};
}

View File

@ -1,4 +1,4 @@
cmake_minimum_required(VERSION 3.24) cmake_minimum_required(VERSION 3.8)
set(CMAKE_EXPORT_COMPILE_COMMANDS OFF) set(CMAKE_EXPORT_COMPILE_COMMANDS OFF)
project(mg_bringup) project(mg_bringup)

View File

@ -1,18 +0,0 @@
# Automatically generated by: ros2nix --distro jazzy
{ lib, buildRosPackage, ament-cmake, launch, launch-ros, mg-control, mg-navigation, mg-odometry }:
buildRosPackage rec {
pname = "ros-jazzy-mg-bringup";
version = "0.0.0";
src = ./.;
buildType = "ament_cmake";
buildInputs = [ ament-cmake ];
propagatedBuildInputs = [ launch launch-ros mg-control mg-navigation mg-odometry ];
nativeBuildInputs = [ ament-cmake ];
meta = {
description = "TODO: Package description";
license = with lib.licenses; [ asl20 ];
};
}

View File

@ -1,4 +1,4 @@
cmake_minimum_required(VERSION 3.24) cmake_minimum_required(VERSION 3.12)
project(mg_bt) project(mg_bt)
set(CMAKE_CXX_STANDARD 17) set(CMAKE_CXX_STANDARD 17)
@ -37,7 +37,6 @@ set(SOURCES
add_executable(mg_bt_executor ${SOURCES}) add_executable(mg_bt_executor ${SOURCES})
add_executable(mg_i2cnode i2cmodule/i2cnode.cpp)
target_include_directories( target_include_directories(
mg_bt_executor mg_bt_executor
@ -46,14 +45,10 @@ target_include_directories(
include include
) )
target_link_libraries(mg_i2cnode i2c)
ament_target_dependencies(mg_bt_executor ${PACKAGE_DEPS}) ament_target_dependencies(mg_bt_executor ${PACKAGE_DEPS})
ament_target_dependencies(mg_i2cnode rclcpp mg_msgs)
install( TARGETS install( TARGETS
mg_bt_executor mg_bt_executor
mg_i2cnode
DESTINATION lib/${PROJECT_NAME} DESTINATION lib/${PROJECT_NAME}
) )

View File

@ -1,47 +0,0 @@
#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 > 255 || 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

@ -1,19 +0,0 @@
# Automatically generated by: ros2nix --distro jazzy
{ lib, buildRosPackage, ament-cmake, ament-lint-auto, ament-lint-common, behaviortree-cpp, behaviortree-ros2, btcpp-ros2-interfaces, i2c-tools, mg-msgs, rclcpp }:
buildRosPackage rec {
pname = "ros-jazzy-mg-bt";
version = "0.0.0";
src = ./.;
buildType = "ament_cmake";
buildInputs = [ ament-cmake ];
checkInputs = [ ament-lint-auto ament-lint-common ];
propagatedBuildInputs = [ behaviortree-cpp behaviortree-ros2 btcpp-ros2-interfaces i2c-tools mg-msgs rclcpp ];
nativeBuildInputs = [ ament-cmake ];
meta = {
description = "Behavior for MagRob";
license = with lib.licenses; [ asl20 ];
};
}

View File

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

View File

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

View File

@ -1,29 +0,0 @@
#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;
}
};
}

View File

@ -1,4 +1,4 @@
cmake_minimum_required(VERSION 3.24) cmake_minimum_required(VERSION 3.8)
project(mg_control) project(mg_control)
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
@ -13,6 +13,7 @@ find_package(hardware_interface REQUIRED)
find_package(rclcpp_lifecycle REQUIRED) find_package(rclcpp_lifecycle REQUIRED)
find_package(rclcpp_components REQUIRED) find_package(rclcpp_components REQUIRED)
include(FindPkgConfig) include(FindPkgConfig)
pkg_search_module(LIBSERIAL REQUIRED libserial)
add_library( add_library(
mg_control mg_control
@ -23,11 +24,13 @@ add_library(
target_include_directories( target_include_directories(
mg_control mg_control
PRIVATE PRIVATE
${LIBSERIAL_INCLUDE_DIRS}
include include
) )
target_link_libraries( target_link_libraries(
mg_control mg_control
${LIBSERIAL_LIBRARIES}
) )
ament_target_dependencies( ament_target_dependencies(

View File

@ -55,7 +55,7 @@
</joint> </joint>
<ros2_control name="mg_base" type="system"> <ros2_control name="mg-base" type="system">
<hardware> <hardware>
<plugin>mg_control/MgStepperInterface</plugin> <plugin>mg_control/MgStepperInterface</plugin>
</hardware> </hardware>

View File

@ -55,7 +55,7 @@
</joint> </joint>
<ros2_control name="mg_base" type="system"> <ros2_control name="mg-base" type="system">
<hardware> <hardware>
<plugin>mock_components/GenericSystem</plugin> <plugin>mock_components/GenericSystem</plugin>
<param name="calculate_dynamics">true</param> <param name="calculate_dynamics">true</param>

View File

@ -3,7 +3,7 @@
#include <vector> #include <vector>
#include <string> #include <string>
//#include "libserial/SerialPort.h" #include "libserial/SerialPort.h"
#include "hardware_interface/handle.hpp" #include "hardware_interface/handle.hpp"
#include "hardware_interface/system_interface.hpp" #include "hardware_interface/system_interface.hpp"
using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn; using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
@ -26,7 +26,7 @@ namespace mg {
private: private:
std::string serial_port_name; std::string serial_port_name;
// LibSerial::SerialPort odrive_serial_interface; LibSerial::SerialPort odrive_serial_interface;
double left_wheel_vel_cmd = 0; double left_wheel_vel_cmd = 0;
double left_wheel_pos_state = 0; double left_wheel_pos_state = 0;

View File

@ -1,19 +0,0 @@
# Automatically generated by: ros2nix --distro jazzy
{ lib, buildRosPackage, ament-cmake, ament-lint-auto, ament-lint-common, controller-manager, diff-drive-controller, hardware-interface, joint-state-broadcaster, libserial-dev, pluginlib, rclcpp, rclcpp-components, rclcpp-lifecycle, robot-state-publisher, ros2-control, ros2launch }:
buildRosPackage rec {
pname = "ros-jazzy-mg-control";
version = "0.0.1";
src = ./.;
buildType = "ament_cmake";
buildInputs = [ ament-cmake ];
checkInputs = [ ament-lint-auto ament-lint-common ];
propagatedBuildInputs = [ controller-manager diff-drive-controller hardware-interface joint-state-broadcaster libserial-dev pluginlib rclcpp rclcpp-components rclcpp-lifecycle robot-state-publisher ros2-control ros2launch ];
nativeBuildInputs = [ ament-cmake ];
meta = {
description = "Ros2 control compatible drivers for magrob";
license = with lib.licenses; [ asl20 ];
};
}

View File

@ -8,13 +8,11 @@ CallbackReturn mg::MgStepperInterface::on_init(const hardware_interface::Hardwar
return CallbackReturn::ERROR; return CallbackReturn::ERROR;
} }
/*
if (info_.hardware_parameters.find("device_path") != info.hardware_parameters.end()) { if (info_.hardware_parameters.find("device_path") != info.hardware_parameters.end()) {
serial_port_name = info_.hardware_parameters["device_path"]; serial_port_name = info_.hardware_parameters["device_path"];
} else { } else {
serial_port_name = "/dev/ttyACM1"; serial_port_name = "/dev/ttyACM1";
} }
*/
left_wheel_pos_state = 0; left_wheel_pos_state = 0;
right_wheel_pos_state = 0; right_wheel_pos_state = 0;
@ -24,7 +22,6 @@ CallbackReturn mg::MgStepperInterface::on_init(const hardware_interface::Hardwar
} }
CallbackReturn mg::MgStepperInterface::on_configure(const rclcpp_lifecycle::State&) { CallbackReturn mg::MgStepperInterface::on_configure(const rclcpp_lifecycle::State&) {
/*
try { try {
if (!odrive_serial_interface.IsOpen()) { if (!odrive_serial_interface.IsOpen()) {
odrive_serial_interface.Open(serial_port_name); odrive_serial_interface.Open(serial_port_name);
@ -34,16 +31,13 @@ CallbackReturn mg::MgStepperInterface::on_configure(const rclcpp_lifecycle::Stat
"Failed to open serial port (Is the stepper driver plugged in)"); "Failed to open serial port (Is the stepper driver plugged in)");
return CallbackReturn::ERROR; return CallbackReturn::ERROR;
} }
*/
return CallbackReturn::SUCCESS; return CallbackReturn::SUCCESS;
} }
CallbackReturn mg::MgStepperInterface::on_shutdown(const rclcpp_lifecycle::State&) { CallbackReturn mg::MgStepperInterface::on_shutdown(const rclcpp_lifecycle::State&) {
/*
if (odrive_serial_interface.IsOpen()) { if (odrive_serial_interface.IsOpen()) {
odrive_serial_interface.Close(); odrive_serial_interface.Close();
} }
*/
return CallbackReturn::SUCCESS; return CallbackReturn::SUCCESS;
} }
@ -72,7 +66,6 @@ hardware_interface::return_type mg::MgStepperInterface::read(const rclcpp::Time&
} }
hardware_interface::return_type mg::MgStepperInterface::write(const rclcpp::Time&, const rclcpp::Duration&) { hardware_interface::return_type mg::MgStepperInterface::write(const rclcpp::Time&, const rclcpp::Duration&) {
/*
union { union {
std::array<u_char, sizeof(double)> bytes; std::array<u_char, sizeof(double)> bytes;
double data; double data;
@ -86,6 +79,5 @@ hardware_interface::return_type mg::MgStepperInterface::write(const rclcpp::Time
for (const auto& bt : value.bytes) { odrive_serial_interface.WriteByte(bt); } for (const auto& bt : value.bytes) { odrive_serial_interface.WriteByte(bt); }
} catch (const std::runtime_error& e) { return hardware_interface::return_type::ERROR; } } catch (const std::runtime_error& e) { return hardware_interface::return_type::ERROR; }
*/
return hardware_interface::return_type::OK; return hardware_interface::return_type::OK;
} }

View File

@ -1,4 +1,4 @@
cmake_minimum_required(VERSION 3.24) cmake_minimum_required(VERSION 3.12)
project(mg_lidar) project(mg_lidar)
set(CMAKE_CXX_STANDARD 17) set(CMAKE_CXX_STANDARD 17)

View File

@ -1,19 +0,0 @@
# Automatically generated by: ros2nix --distro jazzy
{ lib, buildRosPackage, ament-cmake, ament-lint-auto, ament-lint-common, mg-msgs, rclcpp, sensor-msgs, std-msgs, tf2, tf2-geometry-msgs, tf2-ros, visualization-msgs }:
buildRosPackage rec {
pname = "ros-jazzy-mg-lidar";
version = "0.0.0";
src = ./.;
buildType = "ament_cmake";
buildInputs = [ ament-cmake ];
checkInputs = [ ament-lint-auto ament-lint-common ];
propagatedBuildInputs = [ mg-msgs rclcpp sensor-msgs std-msgs tf2 tf2-geometry-msgs tf2-ros visualization-msgs ];
nativeBuildInputs = [ ament-cmake ];
meta = {
description = "Lidar based opponent tracking";
license = with lib.licenses; [ asl20 ];
};
}

View File

@ -8,7 +8,6 @@
#include "tf2_ros/transform_listener.h" #include "tf2_ros/transform_listener.h"
#include "tf2/convert.hpp" #include "tf2/convert.hpp"
#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp" #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
#define GLM_ENABLE_EXPERIMENTAL
#include <glm/gtx/norm.hpp> #include <glm/gtx/norm.hpp>
class MgScanner : public rclcpp::Node { class MgScanner : public rclcpp::Node {

View File

@ -1,4 +1,4 @@
cmake_minimum_required(VERSION 3.24) cmake_minimum_required(VERSION 3.8)
project(mg_msgs) project(mg_msgs)
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
@ -19,7 +19,6 @@ rosidl_generate_interfaces(${PROJECT_NAME}
"action/Rotate.action" "action/Rotate.action"
"srv/CalcPath.srv" "srv/CalcPath.srv"
"srv/SendDouble.srv" "srv/SendDouble.srv"
"srv/I2c.srv"
) )
ament_package() ament_package()

View File

@ -1,18 +0,0 @@
# Automatically generated by: ros2nix --distro jazzy
{ lib, buildRosPackage, ament-cmake, rosidl-default-generators, rosidl-default-runtime }:
buildRosPackage rec {
pname = "ros-jazzy-mg-msgs";
version = "0.0.0";
src = ./.;
buildType = "ament_cmake";
buildInputs = [ ament-cmake rosidl-default-generators ];
propagatedBuildInputs = [ rosidl-default-runtime ];
nativeBuildInputs = [ ament-cmake rosidl-default-generators ];
meta = {
description = "This contains various msg/action used within the project";
license = with lib.licenses; [ mit ];
};
}

View File

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

View File

@ -1,4 +1,4 @@
cmake_minimum_required(VERSION 3.24) cmake_minimum_required(VERSION 3.8)
project(mg_navigation) project(mg_navigation)
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")

View File

@ -1,18 +0,0 @@
# Automatically generated by: ros2nix --distro jazzy
{ lib, buildRosPackage, ament-cmake, geometry-msgs, glm, mg-msgs, mg-obstacles, rclcpp, rclcpp-action, rclcpp-components, tf2, tf2-geometry-msgs, tf2-ros }:
buildRosPackage rec {
pname = "ros-jazzy-mg-navigation";
version = "0.0.0";
src = ./.;
buildType = "ament_cmake";
buildInputs = [ ament-cmake glm ];
propagatedBuildInputs = [ geometry-msgs mg-msgs mg-obstacles rclcpp rclcpp-action rclcpp-components tf2 tf2-geometry-msgs tf2-ros ];
nativeBuildInputs = [ ament-cmake ];
meta = {
description = "TODO: Package description";
license = with lib.licenses; [ asl20 ];
};
}

View File

@ -2,7 +2,6 @@
#include <functional> #include <functional>
#include <thread> #include <thread>
#define GLM_ENABLE_EXPERIMENTAL
#include "rclcpp/rclcpp.hpp" #include "rclcpp/rclcpp.hpp"
#include "mg_navigation.hpp" #include "mg_navigation.hpp"
#include "handlers/dwa.hpp" #include "handlers/dwa.hpp"

View File

@ -1,6 +1,5 @@
#include "path_buffer.hpp" #include "path_buffer.hpp"
#define GLM_ENABLE_EXPERIMENTAL
#include <glm/gtx/norm.hpp> #include <glm/gtx/norm.hpp>
#include <chrono> #include <chrono>

View File

@ -1,7 +1,7 @@
#pragma once #pragma once
#include <glm/glm.hpp> #include <glm/glm.hpp>
#include <json/json.h> #include <jsoncpp/json/json.h>
namespace mg { namespace mg {
class PermanentObstacle { class PermanentObstacle {

View File

@ -1,7 +1,7 @@
#pragma once #pragma once
#include <glm/glm.hpp> #include <glm/glm.hpp>
#include <json/json.h> #include <jsoncpp/json/json.h>
namespace mg { namespace mg {
class StaticObstacle { class StaticObstacle {

View File

@ -1,18 +0,0 @@
# Automatically generated by: ros2nix --distro jazzy
{ lib, buildRosPackage, ament-cmake, geometry-msgs, glm, jsoncpp, mg-msgs, rclcpp, rclcpp-action, rclcpp-components, tf2, tf2-geometry-msgs, tf2-ros }:
buildRosPackage rec {
pname = "ros-jazzy-mg-obstacles";
version = "0.0.0";
src = ./.;
buildType = "ament_cmake";
buildInputs = [ ament-cmake glm ];
propagatedBuildInputs = [ geometry-msgs jsoncpp mg-msgs rclcpp rclcpp-action rclcpp-components tf2 tf2-geometry-msgs tf2-ros ];
nativeBuildInputs = [ ament-cmake ];
meta = {
description = "Library for collision detection";
license = with lib.licenses; [ asl20 ];
};
}

View File

@ -5,7 +5,6 @@
#include "geometry_msgs/msg/point_stamped.hpp" #include "geometry_msgs/msg/point_stamped.hpp"
#include "rclcpp/rclcpp.hpp" #include "rclcpp/rclcpp.hpp"
#define GLM_ENABLE_EXPERIMENTAL
#include "glm/glm.hpp" #include "glm/glm.hpp"
#include "glm/gtx/matrix_transform_2d.hpp" #include "glm/gtx/matrix_transform_2d.hpp"

View File

@ -1,5 +1,4 @@
#include "mg_obstacles/sdf.hpp" #include "mg_obstacles/sdf.hpp"
#define GLM_ENABLE_EXPERIMENTAL
#include <glm/gtx/norm.hpp> #include <glm/gtx/norm.hpp>
namespace mg { namespace mg {

View File

@ -1,4 +1,4 @@
cmake_minimum_required(VERSION 3.24) cmake_minimum_required(VERSION 3.8)
project(mg_odometry) project(mg_odometry)
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
@ -14,6 +14,7 @@ find_package(tf2_geometry_msgs REQUIRED)
find_package(std_srvs REQUIRED) find_package(std_srvs REQUIRED)
find_package(mg_msgs REQUIRED) find_package(mg_msgs REQUIRED)
include(FindPkgConfig) include(FindPkgConfig)
pkg_search_module(LIBSERIAL REQUIRED libserial)
# uncomment the following section in order to fill in # uncomment the following section in order to fill in
# further dependencies manually. # further dependencies manually.
@ -35,10 +36,11 @@ ament_target_dependencies(
target_include_directories(mg_odom_publisher PUBLIC target_include_directories(mg_odom_publisher PUBLIC
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include> $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include/${PROJECT_NAME}> $<INSTALL_INTERFACE:include/${PROJECT_NAME}>
) ${LIBSERIAL_INCLUDE_DIRS})
target_link_libraries( target_link_libraries(
mg_odom_publisher mg_odom_publisher
${LIBSERIAL_LIBRARIES}
) )
target_compile_features(mg_odom_publisher PUBLIC c_std_99 cxx_std_17) # Require C99 and C++17 target_compile_features(mg_odom_publisher PUBLIC c_std_99 cxx_std_17) # Require C99 and C++17

View File

@ -1,19 +0,0 @@
# Automatically generated by: ros2nix --distro jazzy
{ lib, buildRosPackage, ament-cmake, ament-lint-auto, ament-lint-common, libserial-dev, mg-msgs, rclcpp, std-srvs, tf2, tf2-geometry-msgs, tf2-ros }:
buildRosPackage rec {
pname = "ros-jazzy-mg-odometry";
version = "0.0.0";
src = ./.;
buildType = "ament_cmake";
buildInputs = [ ament-cmake ];
checkInputs = [ ament-lint-auto ament-lint-common ];
propagatedBuildInputs = [ mg-msgs rclcpp std-srvs tf2 tf2-geometry-msgs tf2-ros ];
nativeBuildInputs = [ ament-cmake ];
meta = {
description = "TODO: Package description";
license = with lib.licenses; [ "TODO-License-declaration" ];
};
}

View File

@ -5,7 +5,7 @@
#include <memory> #include <memory>
#include <rclcpp/service.hpp> #include <rclcpp/service.hpp>
#include <string> #include <string>
//#include <libserial/SerialStream.h> #include <libserial/SerialStream.h>
#include <sys/types.h> #include <sys/types.h>
#include "mg_msgs/srv/send_double.hpp" #include "mg_msgs/srv/send_double.hpp"
@ -59,11 +59,11 @@ class MgOdomPublisher : public rclcpp::Node {
rclcpp::Service<ZeroSrv>::SharedPtr zero_service_; rclcpp::Service<ZeroSrv>::SharedPtr zero_service_;
rclcpp::Service<ZeroSrv>::SharedPtr calib_service_; rclcpp::Service<ZeroSrv>::SharedPtr calib_service_;
rclcpp::TimerBase::SharedPtr timer_; rclcpp::TimerBase::SharedPtr timer_;
//LibSerial::SerialStream enc_serial_port_; LibSerial::SerialStream enc_serial_port_;
void set_width(const std::shared_ptr<SendDoubleSrv::Request> request) { void set_width(const std::shared_ptr<SendDoubleSrv::Request> request) {
RCLCPP_INFO(get_logger(), "Setting width to: %lf", request->data); RCLCPP_INFO(get_logger(), "Setting width to: %lf", request->data);
/*
if (enc_serial_port_.IsOpen()) { if (enc_serial_port_.IsOpen()) {
union { union {
std::array<u_char, sizeof(double)> bytes; std::array<u_char, sizeof(double)> bytes;
@ -74,12 +74,11 @@ class MgOdomPublisher : public rclcpp::Node {
enc_serial_port_ << "w;"; enc_serial_port_ << "w;";
for (const auto& byte : value.bytes) { enc_serial_port_ << byte; } for (const auto& byte : value.bytes) { enc_serial_port_ << byte; }
} }
*/
} }
void set_ratio(const std::shared_ptr<SendDoubleSrv::Request> request) { void set_ratio(const std::shared_ptr<SendDoubleSrv::Request> request) {
RCLCPP_INFO(get_logger(), "Setting wheel ratio to: %lf", request->data); RCLCPP_INFO(get_logger(), "Setting wheel ratio to: %lf", request->data);
/*
if (enc_serial_port_.IsOpen()) { if (enc_serial_port_.IsOpen()) {
union { union {
std::array<u_char, sizeof(double)> bytes; std::array<u_char, sizeof(double)> bytes;
@ -90,13 +89,11 @@ class MgOdomPublisher : public rclcpp::Node {
enc_serial_port_ << "r;"; enc_serial_port_ << "r;";
for (const auto& byte : value.bytes) { enc_serial_port_ << byte; } for (const auto& byte : value.bytes) { enc_serial_port_ << byte; }
} }
*/
} }
void calib(const std::shared_ptr<ZeroSrv::Request> /*request*/) { void calib(const std::shared_ptr<ZeroSrv::Request> /*request*/) {
RCLCPP_INFO(get_logger(), "Finishing wheel diameter calib"); RCLCPP_INFO(get_logger(), "Finishing wheel diameter calib");
/*
if (enc_serial_port_.IsOpen()) { if (enc_serial_port_.IsOpen()) {
enc_serial_port_ << "c;"; enc_serial_port_ << "c;";
double left_gain = 0; double left_gain = 0;
@ -104,16 +101,14 @@ class MgOdomPublisher : public rclcpp::Node {
enc_serial_port_ >> left_gain >> right_gain; enc_serial_port_ >> left_gain >> right_gain;
RCLCPP_INFO(this->get_logger(), "The new gains are %lf %lf", left_gain, right_gain); RCLCPP_INFO(this->get_logger(), "The new gains are %lf %lf", left_gain, right_gain);
} }
*/
} }
void zero(const std::shared_ptr<ZeroSrv::Request> /*request*/) { void zero(const std::shared_ptr<ZeroSrv::Request> /*request*/) {
RCLCPP_INFO(get_logger(), "Zeroing odometry"); RCLCPP_INFO(get_logger(), "Zeroing odometry");
/*
if (enc_serial_port_.IsOpen()) { if (enc_serial_port_.IsOpen()) {
enc_serial_port_ << "z;"; enc_serial_port_ << "z;";
} }
*/
} }
void timer_callback() { void timer_callback() {
@ -123,7 +118,6 @@ class MgOdomPublisher : public rclcpp::Node {
RCLCPP_DEBUG(this->get_logger(), "Callback called"); RCLCPP_DEBUG(this->get_logger(), "Callback called");
/*
try { try {
if (!enc_serial_port_.IsOpen()) { if (!enc_serial_port_.IsOpen()) {
enc_serial_port_.Open(this->get_parameter("serial_path").as_string()); enc_serial_port_.Open(this->get_parameter("serial_path").as_string());
@ -140,7 +134,6 @@ class MgOdomPublisher : public rclcpp::Node {
make_transform(_x, _y, _theta); make_transform(_x, _y, _theta);
} catch (const std::exception& e) { RCLCPP_ERROR(this->get_logger(), "%s\n", e.what()); } } catch (const std::exception& e) { RCLCPP_ERROR(this->get_logger(), "%s\n", e.what()); }
*/
} }
void make_transform(double x, double y, double theta) { void make_transform(double x, double y, double theta) {

View File

@ -1,4 +1,4 @@
cmake_minimum_required(VERSION 3.24) cmake_minimum_required(VERSION 3.8)
project(mg_planner) project(mg_planner)
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
@ -35,7 +35,6 @@ add_executable(mg_planner
src/a_star.cpp src/a_star.cpp
) )
ament_target_dependencies(mg_planner ${PACKAGE_DEPS}) ament_target_dependencies(mg_planner ${PACKAGE_DEPS})
target_include_directories( target_include_directories(
@ -50,8 +49,6 @@ target_link_libraries(
${LIBGLM_LIBRARIES} ${LIBGLM_LIBRARIES}
) )
target_compile_definitions(mg_planner PRIVATE GLM_ENABLE_EXPERIMENTAL)
install( TARGETS install( TARGETS
mg_planner mg_planner
DESTINATION lib/${PROJECT_NAME} DESTINATION lib/${PROJECT_NAME}

View File

@ -3,7 +3,6 @@
#include "mg_planner/config.hpp" #include "mg_planner/config.hpp"
#include "rclcpp/node.hpp" #include "rclcpp/node.hpp"
#define GLM_ENABLE_EXPERIMENTAL
#include <glm/fwd.hpp> #include <glm/fwd.hpp>
#include <glm/glm.hpp> #include <glm/glm.hpp>
#include <glm/gtx/fast_square_root.hpp> #include <glm/gtx/fast_square_root.hpp>

View File

@ -1,18 +0,0 @@
# Automatically generated by: ros2nix --distro jazzy
{ lib, buildRosPackage, ament-cmake, glm, mg-msgs, mg-obstacles, rclcpp, rclcpp-action, tf2, tf2-geometry-msgs, tf2-ros }:
buildRosPackage rec {
pname = "ros-jazzy-mg-planner";
version = "0.0.0";
src = ./.;
buildType = "ament_cmake";
buildInputs = [ ament-cmake glm ];
propagatedBuildInputs = [ mg-msgs mg-obstacles rclcpp rclcpp-action tf2 tf2-geometry-msgs tf2-ros ];
nativeBuildInputs = [ ament-cmake ];
meta = {
description = "TODO: Package description";
license = with lib.licenses; [ asl20 ];
};
}