1 Commits

Author SHA1 Message Date
d8b55f08de First flake environment 2025-11-06 15:59:22 +01:00
53 changed files with 384 additions and 816 deletions

View File

@@ -1,5 +0,0 @@
{
"clangd.arguments": [
"--query-driver=/usr/bin/arm-none-eabi-g*"
]
}

View File

@@ -10,7 +10,6 @@
#define SM_B 1 #define SM_B 1
#define PULSE_PER_REV (1 / 3200.0) #define PULSE_PER_REV (1 / 3200.0)
#define SPEED_SET_TIMEOUT 1000
//############################################### //###############################################
//================ CONFIG ENCODERS ===================== //================ CONFIG ENCODERS =====================

View File

@@ -32,7 +32,6 @@ static double wheel_ratio_r = 1;
static uint prev_time; static uint prev_time;
static int prev_position_l = 0; static int prev_position_l = 0;
static int prev_position_r = 0; static int prev_position_r = 0;
static uint last_speed_change = 100;
static unsigned char stepper_instr[2+sizeof(double)*2] = {}; static unsigned char stepper_instr[2+sizeof(double)*2] = {};
@@ -213,7 +212,6 @@ void stepper_fifo(char c, uint8_t itf) {
double vr = btod(stepper_instr + 10); double vr = btod(stepper_instr + 10);
set_speeds(vl, vr); set_speeds(vl, vr);
last_speed_change = SPEED_SET_TIMEOUT;
// tud_cdc_n_write(itf, (uint8_t const *) stepper_instr, 18); // tud_cdc_n_write(itf, (uint8_t const *) stepper_instr, 18);
// tud_cdc_n_write_flush(itf); // tud_cdc_n_write_flush(itf);
@@ -265,10 +263,6 @@ int main()
while (true) { while (true) {
if(last_speed_change--) {
set_speeds(0, 0);
last_speed_change = SPEED_SET_TIMEOUT;
}
tud_task(); tud_task();
sleep_ms(1); sleep_ms(1);
} }

84
flake.lock generated Normal file
View File

@@ -0,0 +1,84 @@
{
"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
}

76
flake.nix Normal file
View File

@@ -0,0 +1,76 @@
{
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.8) cmake_minimum_required(VERSION 3.24)
set(CMAKE_EXPORT_COMPILE_COMMANDS OFF) set(CMAKE_EXPORT_COMPILE_COMMANDS OFF)
project(mg_bringup) project(mg_bringup)

View File

@@ -1,63 +0,0 @@
################################################################################
# #
# Launch file meant to be used on the robot itself #
# uses: #
# * mg_control - for sending commands to the stepper drivers #
# * mg_odometry - for reading and controlling the MCU encoders #
# * mg_navigation - runs the local planner and handles move behaviors #
# * mg_navigation - runs the local planner and handles move behaviors #
# * mg_lidar - optionally runs the lidar node to read opponents #
# positions #
# #
################################################################################
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription, GroupAction
from launch.conditions import UnlessCondition
from launch.substitutions import LaunchConfiguration, PathJoinSubstitution, PythonExpression
from launch_ros.actions import Node
from launch_ros.substitutions import FindPackageShare
def generate_launch_description():
is_local_test = DeclareLaunchArgument(
'local_test',
default_value="False",
description='Launch with simulated components'
)
return LaunchDescription([
is_local_test,
IncludeLaunchDescription(
PathJoinSubstitution([
FindPackageShare("mg_control"),
'launch',
'toid.launch.py'
]),
launch_arguments={
'use_mock': LaunchConfiguration('local_test')
}.items()
),
Node(
package="mg_odometry",
executable="mg_odom_publisher",
name="mg_odom_publisher",
condition=UnlessCondition(LaunchConfiguration('local_test')),
parameters=[{
'odom': "odom",
'serial_path': "/dev/ttyACM0",
}],
emulate_tty=True,
output='screen'
),
Node(
package="mg_navigation",
executable="mg_nav_server",
name="mg_nav_server",
emulate_tty=True,
output='screen',
)
])

View File

@@ -1,29 +0,0 @@
################################################################################
# #
# Launch file meant to be used on the robot itself #
# uses: #
# * mg_bt - runs the robot's behavior tree server #
# #
################################################################################
from launch import LaunchDescription
from launch.substitutions import PathJoinSubstitution
from launch_ros.actions import Node
from launch_ros.substitutions import FindPackageShare
def generate_launch_description():
basedir = FindPackageShare("mg_bt")
bt_exec_config = PathJoinSubstitution([basedir, "config/mg_bt_executor.yaml"])
return LaunchDescription([
Node(
package='mg_bt',
executable='mg_bt_executor',
output="screen",
parameters=[bt_exec_config]
),
])

18
mg_bringup/package.nix Normal file
View File

@@ -0,0 +1,18 @@
# 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.12) cmake_minimum_required(VERSION 3.24)
project(mg_bt) project(mg_bt)
set(CMAKE_CXX_STANDARD 17) set(CMAKE_CXX_STANDARD 17)
@@ -37,7 +37,7 @@ set(SOURCES
add_executable(mg_bt_executor ${SOURCES}) add_executable(mg_bt_executor ${SOURCES})
# add_executable(mg_i2cnode i2cmodule/i2cnode.cpp) add_executable(mg_i2cnode i2cmodule/i2cnode.cpp)
target_include_directories( target_include_directories(
mg_bt_executor mg_bt_executor
@@ -46,14 +46,14 @@ target_include_directories(
include include
) )
# target_link_libraries(mg_i2cnode i2c) 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) ament_target_dependencies(mg_i2cnode rclcpp mg_msgs)
install( TARGETS install( TARGETS
mg_bt_executor mg_bt_executor
# mg_i2cnode mg_i2cnode
DESTINATION lib/${PROJECT_NAME} DESTINATION lib/${PROJECT_NAME}
) )

View File

@@ -1,6 +1,5 @@
#include "rclcpp/rclcpp.hpp" #include "rclcpp/rclcpp.hpp"
#include "mg_msgs/srv/i2c.hpp" #include "mg_msgs/srv/i2c.hpp"
extern "C" { extern "C" {
#include <fcntl.h> #include <fcntl.h>
@@ -8,6 +7,7 @@ extern "C" {
#include <sys/ioctl.h> #include <sys/ioctl.h>
#include <i2c/smbus.h> #include <i2c/smbus.h>
} }
class MgI2c : public rclcpp::Node { class MgI2c : public rclcpp::Node {
using I2cSrv = mg_msgs::srv::I2c; using I2cSrv = mg_msgs::srv::I2c;

19
mg_bt/package.nix Normal file
View File

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

@@ -37,7 +37,7 @@ namespace mg {
double theta; double theta;
glm::vec2 pos; glm::vec2 pos;
auto tmsg = tf_buffer_->lookupTransform("odom", "base_footprint", tf2::TimePointZero); auto tmsg = tf_buffer_->lookupTransform("odom", "base-link", tf2::TimePointZero);
tf2::Transform t; tf2::Transform t;
tf2::convert(tmsg.transform, t); tf2::convert(tmsg.transform, t);

View File

@@ -1,4 +1,4 @@
cmake_minimum_required(VERSION 3.8) cmake_minimum_required(VERSION 3.24)
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,7 +13,6 @@ 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
@@ -24,13 +23,11 @@ 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

@@ -1,6 +1,6 @@
controller_manager: controller_manager:
ros__parameters: ros__parameters:
update_rate: 50 update_rate: 100
diffdrive_controller: diffdrive_controller:
type: diff_drive_controller/DiffDriveController type: diff_drive_controller/DiffDriveController
@@ -14,7 +14,7 @@ diffdrive_controller:
enable_odom_tf: false enable_odom_tf: false
odom_frame_id: odom_excpected odom_frame_id: odom_excpected
base_frame_id: base_footprint base_frame_id: base-link
open_loop: true open_loop: true

View File

@@ -14,7 +14,7 @@ diffdrive_controller:
enable_odom_tf: true enable_odom_tf: true
odom_frame_id: odom odom_frame_id: odom
base_frame_id: base_footprint base_frame_id: base-link
open_loop: true open_loop: true

View File

@@ -1,22 +0,0 @@
controller_manager:
ros__parameters:
update_rate: 50
diffdrive_controller:
type: diff_drive_controller/DiffDriveController
joint_state_broadcaster:
type: joint_state_broadcaster/JointStateBroadcaster
diffdrive_controller:
ros__parameters:
left_wheel_names: ["drivewhl_l_joint"]
right_wheel_names: ["drivewhl_r_joint"]
enable_odom_tf: true
odom_frame_id: odom
base_frame_id: base_footprint
open_loop: true
wheel_separation: 0.258
wheel_radius: 0.0375

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,111 +0,0 @@
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.conditions import IfCondition, UnlessCondition
from launch.substitutions import Command, LaunchConfiguration, IfElseSubstitution
from launch_ros.actions import Node, LifecycleNode
from launch_ros.substitutions import FindPackageShare
import os
def generate_launch_description():
pkg_share = FindPackageShare("").find('mg_control')
params = os.path.join(pkg_share, 'assets', 'toid_general_params.yaml')
default_rviz_config_path = os.path.join(pkg_share, 'rviz', 'ros_control.rviz')
description_pkg_share = FindPackageShare("").find('toid_bot_description')
default_model_path = os.path.join(
description_pkg_share,
'src',
'toid_bot_description.urdf'
)
visualize = LaunchConfiguration("visualize")
visualize_arg = DeclareLaunchArgument(
'visualize',
default_value='False',
description="Whether to launch rviz2"
)
use_mock = LaunchConfiguration("use_mock")
use_mock_arg = DeclareLaunchArgument(
'use_mock',
default_value='True',
description="Whether to use mock controller"
)
odom_broadcast = Node(
package='tf2_ros',
executable='static_transform_publisher',
name='map_to_odom_broadcaster',
arguments=['0', '0', '0', '0', '0', '0', 'map', 'odom'],
condition=IfCondition(LaunchConfiguration('visualize'))
)
robot_state_publisher = Node(
package='robot_state_publisher',
executable='robot_state_publisher',
name='robot_state_publisher',
output='screen',
parameters=[{'robot_description': Command(['xacro ', default_model_path, ' use_sim:=', use_mock])}]
)
controller_manager = Node(
package='controller_manager',
executable='ros2_control_node',
output='screen',
parameters=[params]
)
joint_state_broadcaster = Node(
package='controller_manager',
executable='spawner',
output='screen',
arguments=["joint_state_broadcaster"]
)
diffbot_base_controller = Node(
package='controller_manager',
executable='spawner',
output='both',
arguments=[
"diffdrive_controller",
"-p",
params,
"--controller-ros-args",
"-r diffdrive_controller/cmd_vel:=/cmd_vel",
"--controller-ros-args",
"-r diffdrive_controller/odom:=/odom",
"--controller-ros-args",
IfElseSubstitution(use_mock,
"--param odom_frame_id:=odom",
"--param odom_frame_id:=odom_expected"
),
"--controller-ros-args",
IfElseSubstitution(use_mock,
"--param enable_odom_tf:=true",
"--param enable_odom_tf:=false"
),
]
)
rviz_node = Node(
package='rviz2',
executable='rviz2',
name='rviz2',
output='screen',
arguments=['-d', default_rviz_config_path],
condition=IfCondition(visualize)
)
return LaunchDescription([
visualize_arg,
use_mock_arg,
odom_broadcast,
robot_state_publisher,
controller_manager,
joint_state_broadcaster,
diffbot_base_controller,
rviz_node
])

19
mg_control/package.nix Normal file
View File

@@ -0,0 +1,19 @@
# 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,11 +8,13 @@ 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;
@@ -22,6 +24,7 @@ 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);
@@ -31,13 +34,16 @@ 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;
} }
@@ -66,6 +72,7 @@ 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;
@@ -79,5 +86,6 @@ 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.12) cmake_minimum_required(VERSION 3.24)
project(mg_lidar) project(mg_lidar)
set(CMAKE_CXX_STANDARD 17) set(CMAKE_CXX_STANDARD 17)

View File

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

19
mg_lidar/package.nix Normal file
View File

@@ -0,0 +1,19 @@
# 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,6 +8,7 @@
#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 {
@@ -54,7 +55,7 @@ class MgScanner : public rclcpp::Node {
double y = NAN; double y = NAN;
double rot = NAN; double rot = NAN;
auto tmsg = tf_buf_->lookupTransform("odom", "base_footprint", tf2::TimePointZero); auto tmsg = tf_buf_->lookupTransform("odom", "base-link", tf2::TimePointZero);
tf2::Transform t; tf2::Transform t;
tf2::convert(tmsg.transform, t); tf2::convert(tmsg.transform, t);

View File

@@ -1,4 +1,4 @@
cmake_minimum_required(VERSION 3.8) cmake_minimum_required(VERSION 3.24)
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")

18
mg_msgs/package.nix Normal file
View File

@@ -0,0 +1,18 @@
# 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 +1,4 @@
cmake_minimum_required(VERSION 3.8) cmake_minimum_required(VERSION 3.24)
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

@@ -152,7 +152,7 @@ namespace mg {
double x = NAN; double x = NAN;
double y = NAN; double y = NAN;
auto tmsg = tfbuf->lookupTransform("odom", "base_footprint", tf2::TimePointZero); auto tmsg = tfbuf->lookupTransform("odom", "base-link", tf2::TimePointZero);
tf2::Transform t; tf2::Transform t;
tf2::convert(tmsg.transform, t); tf2::convert(tmsg.transform, t);

18
mg_navigation/package.nix Normal file
View File

@@ -0,0 +1,18 @@
# 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,6 +2,7 @@
#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"
@@ -51,7 +52,7 @@ namespace mg {
path_buffer_ = std::make_shared<PathBuffer>(this); path_buffer_ = std::make_shared<PathBuffer>(this);
pub_twist = create_publisher<Geometry::TwistStamped>("/cmd_vel", 2); pub_twist = create_publisher<Geometry::TwistStamped>("diffdrive_controller/cmd_vel", 2);
obstacle_manager_ = std::make_shared<ObstacleManager>(this, tf2_buffer); obstacle_manager_ = std::make_shared<ObstacleManager>(this, tf2_buffer);

View File

@@ -1,5 +1,6 @@
#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 <jsoncpp/json/json.h> #include <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 <jsoncpp/json/json.h> #include <json/json.h>
namespace mg { namespace mg {
class StaticObstacle { class StaticObstacle {

18
mg_obstacles/package.nix Normal file
View File

@@ -0,0 +1,18 @@
# 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,6 +5,7 @@
#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,4 +1,5 @@
#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.8) cmake_minimum_required(VERSION 3.24)
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,7 +14,6 @@ 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.
@@ -36,11 +35,10 @@ 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

19
mg_odometry/package.nix Normal file
View File

@@ -0,0 +1,19 @@
# 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"
@@ -23,7 +23,7 @@
#define TIMEOUT 10u #define TIMEOUT 10u
constexpr const char* ENCODER_SERIAL_PATH_DEFAULT = "/dev/ttyACM0"; constexpr const char* ENCODER_SERIAL_PATH_DEFAULT = "/dev/ttyACM1";
using SendDoubleSrv = mg_msgs::srv::SendDouble; using SendDoubleSrv = mg_msgs::srv::SendDouble;
using ZeroSrv = std_srvs::srv::Empty; using ZeroSrv = std_srvs::srv::Empty;
@@ -32,7 +32,7 @@ class MgOdomPublisher : public rclcpp::Node {
public: public:
MgOdomPublisher() : Node("mg_odom_publisher") { MgOdomPublisher() : Node("mg_odom_publisher") {
this->declare_parameter("odom", "odom"); this->declare_parameter("odom", "odom");
this->declare_parameter("target", "base_footprint"); this->declare_parameter("target", "base-link");
this->declare_parameter("serial_path", ENCODER_SERIAL_PATH_DEFAULT); this->declare_parameter("serial_path", ENCODER_SERIAL_PATH_DEFAULT);
tf_broadcaster_ = std::make_shared<tf2_ros::TransformBroadcaster>(this); tf_broadcaster_ = std::make_shared<tf2_ros::TransformBroadcaster>(this);
@@ -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,11 +74,12 @@ 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;
@@ -89,11 +90,13 @@ 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;
@@ -101,14 +104,16 @@ 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() {
@@ -118,6 +123,7 @@ 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());
@@ -134,6 +140,7 @@ 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.8) cmake_minimum_required(VERSION 3.24)
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,6 +35,7 @@ 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(
@@ -49,6 +50,8 @@ 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,6 +3,7 @@
#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>

18
mg_planner/package.nix Normal file
View File

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

View File

@@ -51,7 +51,7 @@ mg::PlannerNode::PlannerNode() : Node("planner"), astar_(this) {
glm::ivec2 mg::PlannerNode::get_pos() { glm::ivec2 mg::PlannerNode::get_pos() {
try { try {
auto tmsg = tf_buf_->lookupTransform("odom", "base_footprint", tf2::TimePointZero); auto tmsg = tf_buf_->lookupTransform("odom", "base-link", tf2::TimePointZero);
tf2::Transform t; tf2::Transform t;
tf2::convert(tmsg.transform, t); tf2::convert(tmsg.transform, t);

View File

@@ -1,9 +0,0 @@
#!/bin/bash
ros_distro="jazzy"
script_dir=$(dirname "$(readlink -f "${bash_source[0]}")")
source "/opt/ros/${ROS_DISTRO}/setup.bash"
source ./install/setup.bash
ros2 launch mg_bringup base.launch.py $@

View File

@@ -1,19 +0,0 @@
#!/bin/bash
ros_distro="jazzy"
script_dir=$(dirname "$(readlink -f "${bash_source[0]}")")
pids=()
source "/opt/ros/${ROS_DISTRO}/setup.bash"
source "./install/setup.bash"
trap "trap - SIGTERM && kill -- -$$" SIGINT SIGTERM EXIT
ros2 launch mg_bringup bt.launch.py & pids+=($!)
sleep 1
ros2 action send_goal /mg_bt_action_server btcpp_ros2_interfaces/action/ExecuteTree "target_tree: $1" & pids+=($!)
wait

View File

@@ -1,34 +0,0 @@
cmake_minimum_required(VERSION 3.8)
project(toid_bot_description)
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)
# uncomment the following section in order to fill in
# further dependencies manually.
# find_package(<dependency> REQUIRED)
install(
DIRECTORY
src
launch
rviz
DESTINATION share/${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()

View File

@@ -1,17 +0,0 @@
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
copies of the Software, and to permit persons to whom the Software is
furnished to do so, subject to the following conditions:
The above copyright notice and this permission notice shall be included in
all copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL
THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
THE SOFTWARE.

View File

@@ -1,50 +0,0 @@
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.conditions import IfCondition, UnlessCondition
from launch.substitutions import Command, LaunchConfiguration
from launch_ros.actions import Node
from launch_ros.substitutions import FindPackageShare
import os
def generate_launch_description():
pkg_share = FindPackageShare("").find('toid_bot_description')
default_model_path = os.path.join(pkg_share, 'src', 'toid_bot_description.urdf')
default_rviz_config_path = os.path.join(pkg_share, 'rviz', 'default.rviz')
robot_state_publisher_node = Node(
package='robot_state_publisher',
executable='robot_state_publisher',
parameters=[{'robot_description': Command(['xacro ', LaunchConfiguration('model')])}]
)
joint_state_publisher_node = Node(
package='joint_state_publisher',
executable='joint_state_publisher',
name='joint_state_publisher',
parameters=[{'robot_description': Command(['xacro ', default_model_path])}],
condition=UnlessCondition(LaunchConfiguration('gui'))
)
joint_state_publisher_gui_node = Node(
package='joint_state_publisher_gui',
executable='joint_state_publisher_gui',
name='joint_state_publisher_gui',
condition=IfCondition(LaunchConfiguration('gui'))
)
rviz_node = Node(
package='rviz2',
executable='rviz2',
name='rviz2',
output='screen',
arguments=['-d', default_rviz_config_path]
)
return LaunchDescription([
DeclareLaunchArgument(name='gui', default_value='True', description='Flag to enable joint_state_publisher'),
DeclareLaunchArgument(name='model', default_value=default_model_path, description='Path to model'),
robot_state_publisher_node,
joint_state_publisher_node,
joint_state_publisher_gui_node,
rviz_node
])

View File

@@ -1,24 +0,0 @@
<?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>toid_bot_description</name>
<version>0.0.0</version>
<description>TODO: Package description</description>
<maintainer email="example@example.com">pimpest</maintainer>
<license>MIT</license>
<buildtool_depend>ament_cmake</buildtool_depend>
<exec_depend>joint_state_publisher</exec_depend>
<exec_depend>joint_state_publisher_gui</exec_depend>
<exec_depend>robot_state_publisher</exec_depend>
<exec_depend>rviz2</exec_depend>
<exec_depend>xacro</exec_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

@@ -1,235 +0,0 @@
Panels:
- Class: rviz_common/Displays
Help Height: 78
Name: Displays
Property Tree Widget:
Expanded:
- /Global Options1
- /Status1
Splitter Ratio: 0.5
Tree Height: 542
- Class: rviz_common/Selection
Name: Selection
- Class: rviz_common/Tool Properties
Expanded:
- /2D Goal Pose1
- /Publish Point1
Name: Tool Properties
Splitter Ratio: 0.5886790156364441
- Class: rviz_common/Views
Expanded:
- /Current View1
Name: Views
Splitter Ratio: 0.5
- Class: rviz_common/Time
Experimental: false
Name: Time
SyncMode: 0
SyncSource: ""
Visualization Manager:
Class: ""
Displays:
- Alpha: 0.5
Cell Size: 1
Class: rviz_default_plugins/Grid
Color: 160; 160; 164
Enabled: true
Line Style:
Line Width: 0.029999999329447746
Value: Lines
Name: Grid
Normal Cell Count: 0
Offset:
X: 0
Y: 0
Z: 0
Plane: XY
Plane Cell Count: 10
Reference Frame: <Fixed Frame>
Value: true
- Alpha: 0.30000001192092896
Class: rviz_default_plugins/RobotModel
Collision Enabled: false
Description File: ""
Description Source: Topic
Description Topic:
Depth: 5
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
Value: /robot_description
Enabled: true
Links:
All Links Enabled: true
Expand Joint Details: false
Expand Link Details: false
Expand Tree: false
Link Tree Style: Links in Alphabetic Order
base_footprint:
Alpha: 1
Show Axes: false
Show Trail: false
base_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
drivewhl_l_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
drivewhl_r_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
left_caster:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
lidar:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
right_caster:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
Mass Properties:
Inertia: false
Mass: false
Name: RobotModel
TF Prefix: ""
Update Interval: 0
Value: true
Visual Enabled: true
- Class: rviz_default_plugins/TF
Enabled: true
Filter (blacklist): ""
Filter (whitelist): ""
Frame Timeout: 15
Frames:
All Enabled: true
base_footprint:
Value: true
base_link:
Value: true
drivewhl_l_link:
Value: true
drivewhl_r_link:
Value: true
left_caster:
Value: true
lidar:
Value: true
right_caster:
Value: true
Marker Scale: 0.30000001192092896
Name: TF
Show Arrows: true
Show Axes: true
Show Names: true
Tree:
base_link:
base_footprint:
{}
drivewhl_l_link:
{}
drivewhl_r_link:
{}
left_caster:
{}
lidar:
{}
right_caster:
{}
Update Interval: 0
Value: true
Enabled: true
Global Options:
Background Color: 48; 48; 48
Fixed Frame: base_footprint
Frame Rate: 30
Name: root
Tools:
- Class: rviz_default_plugins/Interact
Hide Inactive Objects: true
- Class: rviz_default_plugins/MoveCamera
- Class: rviz_default_plugins/Select
- Class: rviz_default_plugins/FocusCamera
- Class: rviz_default_plugins/Measure
Line color: 128; 128; 0
- Class: rviz_default_plugins/SetInitialPose
Covariance x: 0.25
Covariance y: 0.25
Covariance yaw: 0.06853891909122467
Topic:
Depth: 5
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
Value: /initialpose
- Class: rviz_default_plugins/SetGoal
Topic:
Depth: 5
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
Value: /goal_pose
- Class: rviz_default_plugins/PublishPoint
Single click: true
Topic:
Depth: 5
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
Value: /clicked_point
Transformation:
Current:
Class: rviz_default_plugins/TF
Value: true
Views:
Current:
Class: rviz_default_plugins/XYOrbit
Distance: 1.59040105342865
Enable Stereo Rendering:
Stereo Eye Separation: 0.05999999865889549
Stereo Focal Distance: 1
Swap Stereo Eyes: false
Value: false
Focal Point:
X: 0
Y: 0
Z: 0
Focal Shape Fixed Size: false
Focal Shape Size: 0.05000000074505806
Invert Z Axis: false
Name: Current View
Near Clip Distance: 0.009999999776482582
Pitch: 0.6053992509841919
Target Frame: <Fixed Frame>
Value: XYOrbit (rviz_default_plugins)
Yaw: 1.088563323020935
Saved: ~
Window Geometry:
Displays:
collapsed: false
Height: 846
Hide Left Dock: false
Hide Right Dock: false
QMainWindow State: 000000ff00000000fd00000004000000000000016c000002acfc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005d00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003f000002ac000000cc00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002acfc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003f000002ac000000a900fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004b00000003efc0100000002fb0000000800540069006d00650100000000000004b0000002de00fffffffb0000000800540069006d0065010000000000000450000000000000000000000229000002ac00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
Selection:
collapsed: false
Time:
collapsed: false
Tool Properties:
collapsed: false
Views:
collapsed: false
Width: 1200
X: 60
Y: 60

View File

@@ -1,35 +0,0 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="toid_control" params="name:=toid_control use_mock_hardware:=^|true">
<ros2_control name="${name}" type="system">
<xacro:unless value="${use_mock_hardware}">
<hardware>
<plugin>mg_control/MgStepperInterface</plugin>
</hardware>
</xacro:unless>
<xacro:if value="${use_mock_hardware}">
<hardware>
<plugin>mock_components/GenericSystem</plugin>
<param name="calculate_dynamics">true</param>
</hardware>
</xacro:if>
<joint name="drivewhl_l_joint">
<command_interface name="velocity"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
</joint>
<joint name="drivewhl_r_joint">
<command_interface name="velocity"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
</joint>
</ros2_control>
</xacro:macro>
</robot>

View File

@@ -1,117 +0,0 @@
<?xml version="1.0"?>
<robot name="toid_bot" xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:arg name="use_mock" default="true" />
<xacro:property name="base_width" value="0.30"/>
<xacro:property name="base_length" value="0.30"/>
<xacro:property name="base_height" value="0.34"/>
<xacro:property name="wheel_radius" value="0.04"/>
<xacro:property name="wheel_width" value="0.03"/>
<xacro:property name="wheel_zoff" value="0.03"/>
<xacro:property name="wheel_xoff" value="-0.07"/>
<xacro:property name="wheel_inset" value="0.01"/>
<xacro:property name="caster_radius" value="0.02"/>
<xacro:property name="caster_inset" value="0.04"/>
<xacro:property name="caster_xoff" value="0.10"/>
<xacro:property name="lidar_radius" value="0.03"/>
<xacro:property name="lidar_height" value="0.02"/>
<xacro:property name="lidar_xoff" value="0.09"/>
<xacro:property name="base_zoff" value="${-wheel_zoff + wheel_radius + base_height/2}"/>
<link name="base_link">
<visual>
<geometry>
<box size="${base_length} ${base_width} ${base_height}"/>
</geometry>
<material name="Cyan">
<color rgba="0 1.0 1.0 1.0"/>
</material>
</visual>
</link>
<link name="base_footprint"/>
<link name="lidar">
<visual>
<geometry>
<cylinder radius="${lidar_radius}" length="${lidar_height}"/>
</geometry>
<material name="White">
<color rgba="0.9 0.9 0.9 1.0"/>
</material>
</visual>
</link>
<joint name="base_joint" type="fixed">
<child link="base_link"/>
<parent link="base_footprint"/>
<origin xyz="${-wheel_xoff} 0.0 ${base_zoff}" rpy="0 0 0"/>
</joint>
<joint name="lidar_joint" type="fixed">
<parent link="base_link"/>
<child link="lidar"/>
<origin xyz="${lidar_xoff} 0 ${(base_height + lidar_height)/2}" rpy="0 0 0"/>
</joint>
<xacro:macro name="wheel" params="prefix y_reflect">
<link name="${prefix}_link">
<visual>
<origin xyz="0 0 0" rpy="${pi/2} 0 0"/>
<geometry>
<cylinder radius="${wheel_radius}" length="${wheel_width}"/>
</geometry>
<material name="Yellow">
<color rgba="0.8 0.8 0.3 1.0"/>
</material>
</visual>
</link>
<joint name="${prefix}_joint" type="continuous">
<parent link="base_link"/>
<child link="${prefix}_link"/>
<origin xyz="${wheel_xoff} ${y_reflect*(base_width/2 - wheel_inset)} ${wheel_zoff-base_height/2}" rpy="0 0 0"/>
<axis xyz="0 1 0"/>
</joint>
</xacro:macro>
<xacro:macro name="cstr" params="prefix y_reflect">
<link name="${prefix}_caster">
<visual>
<geometry>
<sphere radius="${caster_radius}"/>
</geometry>
<material name="White">
<color rgba="1.0 1.0 1.0 1.0"/>
</material>
</visual>
</link>
<joint name="${prefix}_caster_joint" type="fixed">
<parent link="base_link"/>
<child link="${prefix}_caster"/>
<origin xyz="${caster_xoff} ${y_reflect*(base_width/2 - caster_inset)} ${caster_radius-base_zoff}" rpy="0 0 0"/>
</joint>
</xacro:macro>
<xacro:wheel prefix="drivewhl_l" y_reflect="1" />
<xacro:wheel prefix="drivewhl_r" y_reflect="-1" />
<xacro:cstr prefix="left" y_reflect="1" />
<xacro:cstr prefix="right" y_reflect="-1" />
<xacro:include filename="$(find toid_bot_description)/src/toid_bot_control.xacro"/>
<xacro:toid_control name="toid_bot_control" use_mock_hardware="$(arg use_mock)"/>
</robot>