Added new robot descriptions for Robotoid

This commit is contained in:
2026-01-05 00:32:35 +01:00
parent 7da27e4cb8
commit b724a7a679
17 changed files with 243 additions and 18 deletions

View File

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

@@ -0,0 +1,29 @@
################################################################################
# #
# 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]
),
])

View File

@@ -37,7 +37,7 @@ set(SOURCES
add_executable(mg_bt_executor ${SOURCES})
add_executable(mg_i2cnode i2cmodule/i2cnode.cpp)
# add_executable(mg_i2cnode i2cmodule/i2cnode.cpp)
target_include_directories(
mg_bt_executor
@@ -46,14 +46,14 @@ target_include_directories(
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_i2cnode rclcpp mg_msgs)
# ament_target_dependencies(mg_i2cnode rclcpp mg_msgs)
install( TARGETS
mg_bt_executor
mg_i2cnode
# mg_i2cnode
DESTINATION lib/${PROJECT_NAME}
)

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

@@ -0,0 +1,111 @@
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
])

View File

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

View File

@@ -54,7 +54,7 @@ class MgScanner : public rclcpp::Node {
double y = NAN;
double rot = NAN;
auto tmsg = tf_buf_->lookupTransform("odom", "base-link", tf2::TimePointZero);
auto tmsg = tf_buf_->lookupTransform("odom", "base_footprint", tf2::TimePointZero);
tf2::Transform t;
tf2::convert(tmsg.transform, t);

View File

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

View File

@@ -51,7 +51,7 @@ namespace mg {
path_buffer_ = std::make_shared<PathBuffer>(this);
pub_twist = create_publisher<Geometry::TwistStamped>("diffdrive_controller/cmd_vel", 2);
pub_twist = create_publisher<Geometry::TwistStamped>("/cmd_vel", 2);
obstacle_manager_ = std::make_shared<ObstacleManager>(this, tf2_buffer);

View File

@@ -23,7 +23,7 @@
#define TIMEOUT 10u
constexpr const char* ENCODER_SERIAL_PATH_DEFAULT = "/dev/ttyACM1";
constexpr const char* ENCODER_SERIAL_PATH_DEFAULT = "/dev/ttyACM0";
using SendDoubleSrv = mg_msgs::srv::SendDouble;
using ZeroSrv = std_srvs::srv::Empty;
@@ -32,7 +32,7 @@ class MgOdomPublisher : public rclcpp::Node {
public:
MgOdomPublisher() : Node("mg_odom_publisher") {
this->declare_parameter("odom", "odom");
this->declare_parameter("target", "base-link");
this->declare_parameter("target", "base_footprint");
this->declare_parameter("serial_path", ENCODER_SERIAL_PATH_DEFAULT);
tf_broadcaster_ = std::make_shared<tf2_ros::TransformBroadcaster>(this);

View File

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

View File

@@ -6,7 +6,7 @@
<ros2_control name="${name}" type="system">
<xacro:unless value="${use_mock_hardware}">
<hardware>
<!-- plugin would eventually go here-->
<plugin>mg_control/MgStepperInterface</plugin>
</hardware>
</xacro:unless>
<xacro:if value="${use_mock_hardware}">