You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
// Initialize serial communication
try {
serial_conn.setPort("/dev/ttyUSB0");
serial_conn.setBaudrate(115200);
serial_conn.open();
RCLCPP_ERROR(rclcpp::get_logger("KevellHardware"), "open a serial port successfully...");
} catch (const serial::IOException &e) {
RCLCPP_ERROR(rclcpp::get_logger("KevellHardware"), "Unable to open serial port: %s", e.what());
return hardware_interface::CallbackReturn::ERROR;
}
if (!serial_conn.isOpen()) {
RCLCPP_ERROR(rclcpp::get_logger("KevellHardware"), "Serial port not open.");
return hardware_interface::CallbackReturn::ERROR;
}
for (const hardware_interface::ComponentInfo & joint : info_.joints)
{
// DiffBotSystem has exactly two states and one command interface on each joint
if (joint.command_interfaces.size() != 1)
{
RCLCPP_FATAL(
rclcpp::get_logger(“DiffDriveArduinoHardware”),
“Joint ‘%s’ has %zu command interfaces found. 1 expected.”, joint.name.c_str(),
joint.command_interfaces.size());
return hardware_interface::CallbackReturn::ERROR;
}
if (joint.state_interfaces.size() != 2)
{
RCLCPP_FATAL(
rclcpp::get_logger("DiffDriveArduinoHardware"),
"Joint '%s' has %zu state interface. 2 expected.", joint.name.c_str(),
joint.state_interfaces.size());
return hardware_interface::CallbackReturn::ERROR;
}
if (joint.state_interfaces[0].name != hardware_interface::HW_IF_POSITION)
{
RCLCPP_FATAL(
rclcpp::get_logger("DiffDriveArduinoHardware"),
"Joint '%s' have '%s' as first state interface. '%s' expected.", joint.name.c_str(),
joint.state_interfaces[0].name.c_str(), hardware_interface::HW_IF_POSITION);
return hardware_interface::CallbackReturn::ERROR;
}
if (joint.state_interfaces[1].name != hardware_interface::HW_IF_VELOCITY)
{
RCLCPP_FATAL(
rclcpp::get_logger("DiffDriveArduinoHardware"),
"Joint '%s' have '%s' as second state interface. '%s' expected.", joint.name.c_str(),
joint.state_interfaces[1].name.c_str(), hardware_interface::HW_IF_VELOCITY);
return hardware_interface::CallbackReturn::ERROR;
}
}
import os
import launch
import launch_ros.actions
from launch.substitutions import Command, FindExecutable, PathJoinSubstitution
from launch_ros.substitutions import FindPackageShare
from ament_index_python.packages import get_package_share_directory
angular.z.has_velocity_limits: false
angular.z.has_acceleration_limits: false
angular.z.has_jerk_limits: false
angular.z.max_velocity: 1.0
angular.z.min_velocity: -1.0
angular.z.max_acceleration: 1.0
angular.z.min_acceleration: -1.0
angular.z.max_jerk: 0.5
angular.z.min_jerk: -0.5
but i got a error is below
kevell@kevell-All-Series:/hardware$ ros2 launch kevell_hardware_interface control_launch.py
[INFO] [launch]: All log files can be found below /home/kevell/.ros/log/2025-02-28-19-03-32-798911-kevell-All-Series-19436
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [ros2_control_node-1]: process started with pid [19439]
[INFO] [robot_state_publisher-2]: process started with pid [19441]
[INFO] [spawner-3]: process started with pid [19443]
[INFO] [spawner-4]: process started with pid [19445]
[ros2_control_node-1] [WARN] [1740749613.110076083] [controller_manager]: [Deprecated] Passing the robot description parameter directly to the control_manager node is deprecated. Use ‘/robot_description’ topic from ‘robot_state_publisher’ instead.
[ros2_control_node-1] [INFO] [1740749613.110290349] [resource_manager]: Loading hardware ‘KevellHardware’
[robot_state_publisher-2] Warning: link ‘chassis’ material ‘white’ undefined.
[robot_state_publisher-2] at line 84 in ./urdf_parser/src/model.cpp
[robot_state_publisher-2] Warning: link ‘chassis’ material ‘white’ undefined.
[robot_state_publisher-2] at line 84 in ./urdf_parser/src/model.cpp
[robot_state_publisher-2] Warning: link ‘left_wheel’ material ‘blue’ undefined.
[robot_state_publisher-2] at line 84 in ./urdf_parser/src/model.cpp
[robot_state_publisher-2] Warning: link ‘left_wheel’ material ‘blue’ undefined.
[robot_state_publisher-2] at line 84 in ./urdf_parser/src/model.cpp
[robot_state_publisher-2] Warning: link ‘right_wheel’ material ‘blue’ undefined.
[robot_state_publisher-2] at line 84 in ./urdf_parser/src/model.cpp
[robot_state_publisher-2] Warning: link ‘right_wheel’ material ‘blue’ undefined.
[robot_state_publisher-2] at line 84 in ./urdf_parser/src/model.cpp
[robot_state_publisher-2] [INFO] [1740749613.111400508] [robot_state_publisher]: got segment base_link
[ros2_control_node-1] [INFO] [1740749613.112011579] [resource_manager]: Initialize hardware ‘KevellHardware’
[ros2_control_node-1] [INFO] [1740749613.112055724] [KevellHardware]: Initializing hardware…
[robot_state_publisher-2] [INFO] [1740749613.112311681] [robot_state_publisher]: got segment chassis
[robot_state_publisher-2] [INFO] [1740749613.112346758] [robot_state_publisher]: got segment left_wheel
[robot_state_publisher-2] [INFO] [1740749613.112363006] [robot_state_publisher]: got segment right_wheel
[ros2_control_node-1] [ERROR] [1740749613.115097096] [KevellHardware]: open a serial port successfully…
[ros2_control_node-1] [INFO] [1740749613.115144954] [KevellHardware]: Hardware initialized successfully.
[ros2_control_node-1] [INFO] [1740749613.115166922] [resource_manager]: Successful initialization of hardware ‘KevellHardware’
[ros2_control_node-1] [INFO] [1740749613.115178039] [KevellHardware]: Exporting state interfaces…
[ros2_control_node-1] [INFO] [1740749613.115286870] [KevellHardware]: Exporting command interfaces…
[ros2_control_node-1] [INFO] [1740749613.115452671] [resource_manager]: ‘configure’ hardware ‘’
[ros2_control_node-1] [INFO] [1740749613.115467618] [resource_manager]: Successful ‘configure’ of hardware ‘’
[ros2_control_node-1] [INFO] [1740749613.115475789] [resource_manager]: ‘activate’ hardware ‘’
[ros2_control_node-1] [INFO] [1740749613.115483704] [KevellHardware]: Activating hardware…
[ros2_control_node-1] [INFO] [1740749613.115491566] [resource_manager]: Successful ‘activate’ of hardware ‘’
[ros2_control_node-1] [INFO] [1740749613.121765422] [controller_manager]: update rate is 10 Hz
[ros2_control_node-1] [WARN] [1740749613.122487251] [controller_manager]: No real-time kernel detected on this system. See [Controller Manager — ROS2_Control: Rolling Feb 2025 documentation] for details on how to enable realtime scheduling.
[ros2_control_node-1] [ERROR] [1740749613.123014530] [KevellHardware]: Invalid encoder data received!
[ros2_control_node-1] [INFO] [1740749613.410553873] [controller_manager]: Loading controller ‘joint_state_broadcaster’
[ros2_control_node-1] [INFO] [1740749613.435844232] [controller_manager]: Loading controller ‘diffbot_base_controller’
[spawner-3] [INFO] [1740749613.444040377] [spawner_joint_state_broadcaster]: Loaded joint_state_broadcaster
[ros2_control_node-1] [INFO] [1740749613.523164696] [controller_manager]: Configuring controller ‘joint_state_broadcaster’
[ros2_control_node-1] [INFO] [1740749613.523369036] [joint_state_broadcaster]: ‘joints’ or ‘interfaces’ parameter is empty. All available state interfaces will be published
[spawner-4] [INFO] [1740749613.542315886] [spawner_diffbot_base_controller]: Loaded diffbot_base_controller
[ros2_control_node-1] [INFO] [1740749613.622852558] [controller_manager]: Configuring controller ‘diffbot_base_controller’
[ros2_control_node-1] [ERROR] [1740749613.822659800] [joint_state_broadcaster]: None of requested interfaces exist. Controller will not run.
[ros2_control_node-1] [WARN] [1740749613.822701272] [joint_state_broadcaster]: Error occurred while doing error handling.
[ros2_control_node-1] [ERROR] [1740749613.822740574] [controller_manager]: After activation, controller ‘joint_state_broadcaster’ is in state ‘unconfigured’ (1), expected ‘active’ (3).
[ros2_control_node-1] [ERROR] [1740749613.923127704] [resource_manager]: Not acceptable command interfaces combination:
[ros2_control_node-1] Start interfaces:
[ros2_control_node-1] [
[ros2_control_node-1] left_wheel_joint/velocity
[ros2_control_node-1] right_wheel_joint/velocity
[ros2_control_node-1] ]
[ros2_control_node-1] Stop interfaces:
[ros2_control_node-1] [
[ros2_control_node-1] ]
[ros2_control_node-1] Not available:
[ros2_control_node-1] [
[ros2_control_node-1] left_wheel_joint/velocity
[ros2_control_node-1] right_wheel_joint/velocity
[ros2_control_node-1] ]
[ros2_control_node-1]
[ros2_control_node-1] [ERROR] [1740749613.923163006] [controller_manager]: Could not switch controllers since prepare command mode switch was rejected.
[spawner-3] [INFO] [1740749613.923917841] [spawner_joint_state_broadcaster]: Configured and activated joint_state_broadcaster
[spawner-4] [ERROR] [1740749613.924526640] [spawner_diffbot_base_controller]: Failed to activate controller
[INFO] [spawner-3]: process has finished cleanly [pid 19443]
[ERROR] [spawner-4]: process has died [pid 19445, exit code 1, cmd ‘/opt/ros/humble/lib/controller_manager/spawner diffbot_base_controller --controller-manager /controller_manager --ros-args’].
^C[WARNING] [launch]: user interrupted with ctrl-c (SIGINT)
[robot_state_publisher-2] [INFO] [1740749623.278484912] [rclcpp]: signal_handler(signum=2)
[ros2_control_node-1] [INFO] [1740749623.278484852] [rclcpp]: signal_handler(signum=2)
[INFO] [ros2_control_node-1]: process has finished cleanly [pid 19439]
[INFO] [robot_state_publisher-2]: process has finished cleanly [pid 19441]
so expertise i have mess about confusion please help for me
The text was updated successfully, but these errors were encountered:
hi i create a custom_hardware_interface using with our tutorial
here is my files one by one
#include “…/include/kevell_hardware_interface/kevell_hardware_interface.hpp”
#include <hardware_interface/types/hardware_interface_type_values.hpp>
hardware_interface::CallbackReturn KevellHardware::on_init(const hardware_interface::HardwareInfo &info) {
RCLCPP_INFO(rclcpp::get_logger(“KevellHardware”), “Initializing hardware…”);
// Initialize serial communication
try {
serial_conn.setPort("/dev/ttyUSB0");
serial_conn.setBaudrate(115200);
serial_conn.open();
RCLCPP_ERROR(rclcpp::get_logger("KevellHardware"), "open a serial port successfully...");
} catch (const serial::IOException &e) {
RCLCPP_ERROR(rclcpp::get_logger("KevellHardware"), "Unable to open serial port: %s", e.what());
return hardware_interface::CallbackReturn::ERROR;
}
if (!serial_conn.isOpen()) {
RCLCPP_ERROR(rclcpp::get_logger("KevellHardware"), "Serial port not open.");
return hardware_interface::CallbackReturn::ERROR;
}
for (const hardware_interface::ComponentInfo & joint : info_.joints)
{
// DiffBotSystem has exactly two states and one command interface on each joint
if (joint.command_interfaces.size() != 1)
{
RCLCPP_FATAL(
rclcpp::get_logger(“DiffDriveArduinoHardware”),
“Joint ‘%s’ has %zu command interfaces found. 1 expected.”, joint.name.c_str(),
joint.command_interfaces.size());
return hardware_interface::CallbackReturn::ERROR;
}
if (joint.command_interfaces[0].name != hardware_interface::HW_IF_VELOCITY)
{
RCLCPP_FATAL(
rclcpp::get_logger("DiffDriveArduinoHardware"),
"Joint '%s' have %s command interfaces found. '%s' expected.", joint.name.c_str(),
joint.command_interfaces[0].name.c_str(), hardware_interface::HW_IF_VELOCITY);
return hardware_interface::CallbackReturn::ERROR;
}
if (joint.state_interfaces.size() != 2)
{
RCLCPP_FATAL(
rclcpp::get_logger("DiffDriveArduinoHardware"),
"Joint '%s' has %zu state interface. 2 expected.", joint.name.c_str(),
joint.state_interfaces.size());
return hardware_interface::CallbackReturn::ERROR;
}
if (joint.state_interfaces[0].name != hardware_interface::HW_IF_POSITION)
{
RCLCPP_FATAL(
rclcpp::get_logger("DiffDriveArduinoHardware"),
"Joint '%s' have '%s' as first state interface. '%s' expected.", joint.name.c_str(),
joint.state_interfaces[0].name.c_str(), hardware_interface::HW_IF_POSITION);
return hardware_interface::CallbackReturn::ERROR;
}
if (joint.state_interfaces[1].name != hardware_interface::HW_IF_VELOCITY)
{
RCLCPP_FATAL(
rclcpp::get_logger("DiffDriveArduinoHardware"),
"Joint '%s' have '%s' as second state interface. '%s' expected.", joint.name.c_str(),
joint.state_interfaces[1].name.c_str(), hardware_interface::HW_IF_VELOCITY);
return hardware_interface::CallbackReturn::ERROR;
}
}
RCLCPP_INFO(rclcpp::get_logger("KevellHardware"), "Hardware initialized successfully.");
return hardware_interface::CallbackReturn::SUCCESS;
}
hardware_interface::CallbackReturn KevellHardware::on_activate(const rclcpp_lifecycle::State &) {
RCLCPP_INFO(rclcpp::get_logger(“KevellHardware”), “Activating hardware…”);
return hardware_interface::CallbackReturn::SUCCESS;
}
hardware_interface::CallbackReturn KevellHardware::on_deactivate(const rclcpp_lifecycle::State &) {
RCLCPP_INFO(rclcpp::get_logger(“KevellHardware”), “Deactivating hardware…”);
return hardware_interface::CallbackReturn::SUCCESS;
}
std::vector<hardware_interface::StateInterface> KevellHardware::export_state_interfaces() {
RCLCPP_INFO(rclcpp::get_logger(“KevellHardware”), “Exporting state interfaces…”);
std::vector<hardware_interface::StateInterface> state_interfaces;
state_interfaces.emplace_back(hardware_interface::StateInterface("left_wheel_joint", hardware_interface::HW_IF_POSITION, &position_states[0]));
state_interfaces.emplace_back(hardware_interface::StateInterface("left_wheel_joint", hardware_interface::HW_IF_VELOCITY, &velocity_states[0]));
state_interfaces.emplace_back(hardware_interface::StateInterface("right_wheel_joint", hardware_interface::HW_IF_POSITION, &position_states[1]));
state_interfaces.emplace_back(hardware_interface::StateInterface("right_wheel_joint", hardware_interface::HW_IF_VELOCITY, &velocity_states[1]));
return state_interfaces;
}
std::vector<hardware_interface::CommandInterface> KevellHardware::export_command_interfaces() {
RCLCPP_INFO(rclcpp::get_logger(“KevellHardware”), “Exporting command interfaces…”);
std::vector<hardware_interface::CommandInterface> command_interfaces;
command_interfaces.emplace_back(hardware_interface::CommandInterface("left_wheel_joint", hardware_interface::HW_IF_VELOCITY, &velocity_commands[0]));
command_interfaces.emplace_back(hardware_interface::CommandInterface("right_wheel_joint", hardware_interface::HW_IF_VELOCITY, &velocity_commands[1]));
return command_interfaces;
}
hardware_interface::return_type KevellHardware::read(const rclcpp::Time &, const rclcpp::Duration &) {
if (!serial_conn.isOpen()) {
RCLCPP_ERROR(rclcpp::get_logger(“KevellHardware”), “Serial connection lost!”);
return hardware_interface::return_type::ERROR;
}
std::string response;
try {
serial_conn.write("READ\n");
response = serial_conn.readline();
} catch (const serial::IOException &e) {
RCLCPP_ERROR(rclcpp::get_logger("KevellHardware"), "Serial read error: %s", e.what());
return hardware_interface::return_type::ERROR;
}
// Example parsing: "ENC 500 480"
int left_encoder, right_encoder;
if (sscanf(response.c_str(), "ENC %d %d", &left_encoder, &right_encoder) == 2) {
position_states[0] = (left_encoder / ticks_per_revolution) * 2 * M_PI;
position_states[1] = (right_encoder / ticks_per_revolution) * 2 * M_PI;
velocity_states[0] = (position_states[0] - left_encoder_prev) / 0.1;
velocity_states[1] = (position_states[1] - right_encoder_prev) / 0.1;
} else {
RCLCPP_ERROR(rclcpp::get_logger("KevellHardware"), "Invalid encoder data received!");
return hardware_interface::return_type::ERROR;
}
return hardware_interface::return_type::OK;
}
hardware_interface::return_type KevellHardware::write(const rclcpp::Time &, const rclcpp::Duration &) {
if (!serial_conn.isOpen()) {
RCLCPP_ERROR(rclcpp::get_logger(“KevellHardware”), “Serial connection lost!”);
return hardware_interface::return_type::ERROR;
}
char command[50];
snprintf(command, sizeof(command), "CMD %.2f %.2f\n", velocity_commands[0], velocity_commands[1]);
try {
serial_conn.write(command);
} catch (const serial::IOException &e) {
RCLCPP_ERROR(rclcpp::get_logger("KevellHardware"), "Serial write error: %s", e.what());
return hardware_interface::return_type::ERROR;
}
return hardware_interface::return_type::OK;
}
#include <pluginlib/class_list_macros.hpp>
PLUGINLIB_EXPORT_CLASS(KevellHardware, hardware_interface::SystemInterface)
and launch file
import os
import launch
import launch_ros.actions
from launch.substitutions import Command, FindExecutable, PathJoinSubstitution
from launch_ros.substitutions import FindPackageShare
from ament_index_python.packages import get_package_share_directory
def generate_launch_description():
robot_description_content = Command(
[
PathJoinSubstitution([FindExecutable(name="xacro")]),
" ",
PathJoinSubstitution(
[FindPackageShare("kevell_hardware_interface"), "urdf", "robot_urdf.xacro"]
),
]
)
robot_description = {"robot_description": robot_description_content}
kevell_hardware_config = os.path.join(
get_package_share_directory('kevell_hardware_interface'), 'config', 'kevell_controllers.yaml'
)
return launch.LaunchDescription([
launch_ros.actions.Node(
package='controller_manager',
executable='ros2_control_node',
parameters=[robot_description,kevell_hardware_config],
output='screen'
),
launch_ros.actions.Node(
package='robot_state_publisher',
executable='robot_state_publisher',
parameters=[robot_description],
output='screen'
),
launch_ros.actions.Node(
package='controller_manager',
executable='spawner',
arguments=["joint_state_broadcaster", "--controller-manager", "/controller_manager"],
output='screen'
),
launch_ros.actions.Node(
package='controller_manager',
executable='spawner',
arguments=["diffbot_base_controller", "--controller-manager", "/controller_manager"],
output='screen'
)
])
and the config file is
controller_manager:
ros__parameters:
update_rate: 10 # Hz
diffbot_base_controller:
type: diff_drive_controller/DiffDriveController
#left_wheel_names: ["left_wheel_joint"]
#right_wheel_names: ["right_wheel_joint"]
#command_interfaces:
#- velocity
#state_interfaces:
#- position
#- velocity
joint_state_broadcaster:
type: joint_state_broadcaster/JointStateBroadcaster
joints: ["left_wheel_joint", "right_wheel_joint"]
diffbot_base_controller:
ros__parameters:
publish_rate: 50.0
left_wheel_names: [“left_wheel_joint”]
right_wheel_names: [“right_wheel_joint”]
wheels_per_side: 1
wheel_separation: 0.3
wheel_radius: 0.05
base_frame_id: base_link
use_stamped_vel: false
linear.x.has_velocity_limits: false
linear.x.has_acceleration_limits: false
linear.x.has_jerk_limits: false
linear.x.max_velocity: 1.0 # Changed from 0.0 to avoid divide-by-zero errors
linear.x.min_velocity: -1.0 # Allow backward motion
linear.x.max_acceleration: 1.0
linear.x.min_acceleration: -1.0
linear.x.max_jerk: 0.5
linear.x.min_jerk: -0.5
angular.z.has_velocity_limits: false
angular.z.has_acceleration_limits: false
angular.z.has_jerk_limits: false
angular.z.max_velocity: 1.0
angular.z.min_velocity: -1.0
angular.z.max_acceleration: 1.0
angular.z.min_acceleration: -1.0
angular.z.max_jerk: 0.5
angular.z.min_jerk: -0.5
but i got a error is below
kevell@kevell-All-Series:
/hardware$ ros2 launch kevell_hardware_interface control_launch.py/robot_description’ topic from ‘robot_state_publisher’ instead.[INFO] [launch]: All log files can be found below /home/kevell/.ros/log/2025-02-28-19-03-32-798911-kevell-All-Series-19436
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [ros2_control_node-1]: process started with pid [19439]
[INFO] [robot_state_publisher-2]: process started with pid [19441]
[INFO] [spawner-3]: process started with pid [19443]
[INFO] [spawner-4]: process started with pid [19445]
[ros2_control_node-1] [WARN] [1740749613.110076083] [controller_manager]: [Deprecated] Passing the robot description parameter directly to the control_manager node is deprecated. Use ‘
[ros2_control_node-1] [INFO] [1740749613.110290349] [resource_manager]: Loading hardware ‘KevellHardware’
[robot_state_publisher-2] Warning: link ‘chassis’ material ‘white’ undefined.
[robot_state_publisher-2] at line 84 in ./urdf_parser/src/model.cpp
[robot_state_publisher-2] Warning: link ‘chassis’ material ‘white’ undefined.
[robot_state_publisher-2] at line 84 in ./urdf_parser/src/model.cpp
[robot_state_publisher-2] Warning: link ‘left_wheel’ material ‘blue’ undefined.
[robot_state_publisher-2] at line 84 in ./urdf_parser/src/model.cpp
[robot_state_publisher-2] Warning: link ‘left_wheel’ material ‘blue’ undefined.
[robot_state_publisher-2] at line 84 in ./urdf_parser/src/model.cpp
[robot_state_publisher-2] Warning: link ‘right_wheel’ material ‘blue’ undefined.
[robot_state_publisher-2] at line 84 in ./urdf_parser/src/model.cpp
[robot_state_publisher-2] Warning: link ‘right_wheel’ material ‘blue’ undefined.
[robot_state_publisher-2] at line 84 in ./urdf_parser/src/model.cpp
[robot_state_publisher-2] [INFO] [1740749613.111400508] [robot_state_publisher]: got segment base_link
[ros2_control_node-1] [INFO] [1740749613.112011579] [resource_manager]: Initialize hardware ‘KevellHardware’
[ros2_control_node-1] [INFO] [1740749613.112055724] [KevellHardware]: Initializing hardware…
[robot_state_publisher-2] [INFO] [1740749613.112311681] [robot_state_publisher]: got segment chassis
[robot_state_publisher-2] [INFO] [1740749613.112346758] [robot_state_publisher]: got segment left_wheel
[robot_state_publisher-2] [INFO] [1740749613.112363006] [robot_state_publisher]: got segment right_wheel
[ros2_control_node-1] [ERROR] [1740749613.115097096] [KevellHardware]: open a serial port successfully…
[ros2_control_node-1] [INFO] [1740749613.115144954] [KevellHardware]: Hardware initialized successfully.
[ros2_control_node-1] [INFO] [1740749613.115166922] [resource_manager]: Successful initialization of hardware ‘KevellHardware’
[ros2_control_node-1] [INFO] [1740749613.115178039] [KevellHardware]: Exporting state interfaces…
[ros2_control_node-1] [INFO] [1740749613.115286870] [KevellHardware]: Exporting command interfaces…
[ros2_control_node-1] [INFO] [1740749613.115452671] [resource_manager]: ‘configure’ hardware ‘’
[ros2_control_node-1] [INFO] [1740749613.115467618] [resource_manager]: Successful ‘configure’ of hardware ‘’
[ros2_control_node-1] [INFO] [1740749613.115475789] [resource_manager]: ‘activate’ hardware ‘’
[ros2_control_node-1] [INFO] [1740749613.115483704] [KevellHardware]: Activating hardware…
[ros2_control_node-1] [INFO] [1740749613.115491566] [resource_manager]: Successful ‘activate’ of hardware ‘’
[ros2_control_node-1] [INFO] [1740749613.121765422] [controller_manager]: update rate is 10 Hz
[ros2_control_node-1] [WARN] [1740749613.122487251] [controller_manager]: No real-time kernel detected on this system. See [Controller Manager — ROS2_Control: Rolling Feb 2025 documentation] for details on how to enable realtime scheduling.
[ros2_control_node-1] [ERROR] [1740749613.123014530] [KevellHardware]: Invalid encoder data received!
[ros2_control_node-1] [INFO] [1740749613.410553873] [controller_manager]: Loading controller ‘joint_state_broadcaster’
[ros2_control_node-1] [INFO] [1740749613.435844232] [controller_manager]: Loading controller ‘diffbot_base_controller’
[spawner-3] [INFO] [1740749613.444040377] [spawner_joint_state_broadcaster]: Loaded joint_state_broadcaster
[ros2_control_node-1] [INFO] [1740749613.523164696] [controller_manager]: Configuring controller ‘joint_state_broadcaster’
[ros2_control_node-1] [INFO] [1740749613.523369036] [joint_state_broadcaster]: ‘joints’ or ‘interfaces’ parameter is empty. All available state interfaces will be published
[spawner-4] [INFO] [1740749613.542315886] [spawner_diffbot_base_controller]: Loaded diffbot_base_controller
[ros2_control_node-1] [INFO] [1740749613.622852558] [controller_manager]: Configuring controller ‘diffbot_base_controller’
[ros2_control_node-1] [ERROR] [1740749613.822659800] [joint_state_broadcaster]: None of requested interfaces exist. Controller will not run.
[ros2_control_node-1] [WARN] [1740749613.822701272] [joint_state_broadcaster]: Error occurred while doing error handling.
[ros2_control_node-1] [ERROR] [1740749613.822740574] [controller_manager]: After activation, controller ‘joint_state_broadcaster’ is in state ‘unconfigured’ (1), expected ‘active’ (3).
[ros2_control_node-1] [ERROR] [1740749613.923127704] [resource_manager]: Not acceptable command interfaces combination:
[ros2_control_node-1] Start interfaces:
[ros2_control_node-1] [
[ros2_control_node-1] left_wheel_joint/velocity
[ros2_control_node-1] right_wheel_joint/velocity
[ros2_control_node-1] ]
[ros2_control_node-1] Stop interfaces:
[ros2_control_node-1] [
[ros2_control_node-1] ]
[ros2_control_node-1] Not available:
[ros2_control_node-1] [
[ros2_control_node-1] left_wheel_joint/velocity
[ros2_control_node-1] right_wheel_joint/velocity
[ros2_control_node-1] ]
[ros2_control_node-1]
[ros2_control_node-1] [ERROR] [1740749613.923163006] [controller_manager]: Could not switch controllers since prepare command mode switch was rejected.
[spawner-3] [INFO] [1740749613.923917841] [spawner_joint_state_broadcaster]: Configured and activated joint_state_broadcaster
[spawner-4] [ERROR] [1740749613.924526640] [spawner_diffbot_base_controller]: Failed to activate controller
[INFO] [spawner-3]: process has finished cleanly [pid 19443]
[ERROR] [spawner-4]: process has died [pid 19445, exit code 1, cmd ‘/opt/ros/humble/lib/controller_manager/spawner diffbot_base_controller --controller-manager /controller_manager --ros-args’].
^C[WARNING] [launch]: user interrupted with ctrl-c (SIGINT)
[robot_state_publisher-2] [INFO] [1740749623.278484912] [rclcpp]: signal_handler(signum=2)
[ros2_control_node-1] [INFO] [1740749623.278484852] [rclcpp]: signal_handler(signum=2)
[INFO] [ros2_control_node-1]: process has finished cleanly [pid 19439]
[INFO] [robot_state_publisher-2]: process has finished cleanly [pid 19441]
so expertise i have mess about confusion please help for me
The text was updated successfully, but these errors were encountered: