Skip to content

Commit

Permalink
fixes
Browse files Browse the repository at this point in the history
  • Loading branch information
MatjazBostic committed Sep 6, 2024
1 parent 44199e6 commit fe59c52
Show file tree
Hide file tree
Showing 5 changed files with 71 additions and 3 deletions.
4 changes: 4 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -193,6 +193,10 @@ install(PROGRAMS
DESTINATION lib/${PROJECT_NAME}
)

install(DIRECTORY launch/
DESTINATION share/${PROJECT_NAME}/launch
)

# # Test dependencies
# if(BUILD_TESTING)
# find_package(ament_lint_auto REQUIRED)
Expand Down
48 changes: 48 additions & 0 deletions cfg/test.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,48 @@
# This is the configuration for the controller_manager in ROS 2
controller_manager:
ros__parameters:
ubiquity_velocity_controller:
type: "diff_drive_controller/DiffDriveController"

# Specify the joints connected to the wheels
left_wheel_names: ['left_wheel_joint']
right_wheel_names: ['right_wheel_joint']

# Publish rate for odometry messages
publish_rate: 50.0 # Same as in ROS 1, rate of odom publishing

# Covariance for pose and twist (six elements representing the covariance matrix diagonal)
pose_covariance_diagonal: [0.2, 0.2, 0.2, 0.2, 0.2, 0.2]
twist_covariance_diagonal: [0.2, 0.2, 0.2, 0.2, 0.2, 0.2]

# Velocity command timeout (stop if no command received after this time)
cmd_vel_timeout: 0.25

# Enable publishing of the transform from odom to base_frame_id
enable_odom_tf: true

# Robot physical parameters
wheel_separation: 0.33
wheel_radius: 0.1015

# Base frame ID for the robot
base_frame_id: base_footprint

# Multipliers to adjust wheel separation and radius (usually left at 1.0)
wheel_separation_multiplier: 1.0
wheel_radius_multiplier: 1.0

# Velocity and acceleration limits for linear and angular motion
linear:
x:
has_velocity_limits: true
max_velocity: 1.0 # Maximum forward speed (m/s)
has_acceleration_limits: true
max_acceleration: 1.1 # Maximum acceleration (m/s^2)

angular:
z:
has_velocity_limits: true
max_velocity: 2.0 # Maximum rotational speed (rad/s)
has_acceleration_limits: true
max_acceleration: 5.0 # Maximum angular acceleration (rad/s^2)
4 changes: 2 additions & 2 deletions include/ubiquity_motor_ros2/motor_parameters.h
Original file line number Diff line number Diff line change
Expand Up @@ -184,10 +184,10 @@ struct CommsParams {
int32_t baud_rate;

CommsParams()
: serial_port("/dev/ttyS0"), baud_rate(9600) {};
: serial_port("/dev/ttyS0"), baud_rate(38400) {};

CommsParams(const std::shared_ptr<rclcpp::Node>& n)
: serial_port("/dev/ttyS0"), baud_rate(9600) {
: serial_port("/dev/ttyS0"), baud_rate(38400) {
// clang-format off
serial_port = getParamOrDefault(
n, "ubiquity_motor_ros2/serial_port", serial_port);
Expand Down
13 changes: 13 additions & 0 deletions launch/test.launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
from launch import LaunchDescription
from launch_ros.actions import Node

def generate_launch_description():
return LaunchDescription([
Node(
package='controller_manager',
executable='spawner', # Correct executable for spawning controllers
arguments=['diff_drive_controller'], # Controller name
parameters=['/home/ubuntu/ros2_ws/src/ubiquity_motor_ros2/cfg/test.yaml'], # Path to your YAML config file
output='screen',
),
])
5 changes: 4 additions & 1 deletion src/motor_node.cc
Original file line number Diff line number Diff line change
Expand Up @@ -178,7 +178,8 @@ void MotorNode::run() {
"--ros-args",
// "--remap", "controller_manager:__node:=motor_hardware_node",
"--log-level", "info",
"--param", "update_rate:=" + std::to_string(controller_loop_rate)
"--param", "update_rate:=" + std::to_string(controller_loop_rate),
"--params-file", "/home/ubuntu/ros2_ws/src/ubiquity_motor_ros2/cfg/test.yaml"
});


Expand All @@ -190,6 +191,8 @@ void MotorNode::run() {
// Create the ResourceManager and register the actuator interface
auto resource_manager = std::make_unique<hardware_interface::ResourceManager>(buffer.str(), get_node_clock_interface(), get_node_logging_interface(), true, controller_loop_rate);
resource_manager->import_component(std::move(robot), getHwInfo());
// resource_manager->load_hardware_component(std::move(robot), getHwInfo());


controller_manager::ControllerManager cm(std::move(resource_manager), executor, "controller_manager", get_namespace(), options);

Expand Down

0 comments on commit fe59c52

Please sign in to comment.