ros-industrial / ros2_canopen

CANopen driver framework for ROS2
https://ros-industrial.github.io/ros2_canopen/manual/rolling/
131 stars 55 forks source link

Controller Manager Not available #180

Closed jclinton830 closed 4 months ago

jclinton830 commented 1 year ago

Describe the bug

I am working on a robot with 4 wheels, each wheel has its own drive and steer motors. Making it a total of 8 motor nodes that are driven via the CAN bus.

I am using the Cia402Driver and the ros2_control support provided by the robot_system_interface. After starting the can0 network with the real robot hardware and starting my launch file I get the following error.

The question is, why is the controller manager not available? Currently, I only have one wheel assembled. So that is two motor controller devices on the bus. The second question is why is it that only one joint (fl_drive_joint) is being added to the executor and the rest are not being configured or even being attempted to be configured?

I am new to this ros2_canopen package so any help here would be greatly appreciated.

jerome@jjustin:~/gh_ws$ ros2 launch groundhog_control canopen_system.launch.py 
[INFO] [launch]: All log files can be found below /home/jerome/.ros/log/2023-07-28-14-31-27-437335-jjustin-164093
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [ros2_control_node-1]: process started with pid [164097]
[INFO] [robot_state_publisher-2]: process started with pid [164099]
[INFO] [spawner-3]: process started with pid [164101]
[INFO] [spawner-4]: process started with pid [164103]
[robot_state_publisher-2] [WARN] [1690518688.061029386] [kdl_parser]: The root link base_link has an inertia specified in the URDF, but KDL does not support a root link with an inertia.  As a workaround, you can add an extra dummy link to your URDF.
[robot_state_publisher-2] [INFO] [1690518688.061095983] [robot_state_publisher]: got segment base_link
[robot_state_publisher-2] [INFO] [1690518688.061131604] [robot_state_publisher]: got segment fl_steer_link
[robot_state_publisher-2] [INFO] [1690518688.061136117] [robot_state_publisher]: got segment fl_wheel_link
[robot_state_publisher-2] [INFO] [1690518688.061139414] [robot_state_publisher]: got segment fr_steer_link
[robot_state_publisher-2] [INFO] [1690518688.061142312] [robot_state_publisher]: got segment fr_wheel_link
[robot_state_publisher-2] [INFO] [1690518688.061145430] [robot_state_publisher]: got segment rl_steer_link
[robot_state_publisher-2] [INFO] [1690518688.061148693] [robot_state_publisher]: got segment rl_wheel_link
[robot_state_publisher-2] [INFO] [1690518688.061151580] [robot_state_publisher]: got segment rr_steer_link
[robot_state_publisher-2] [INFO] [1690518688.061154414] [robot_state_publisher]: got segment rr_wheel_link
[ros2_control_node-1] [INFO] [1690518688.068102232] [resource_manager]: Loading hardware 'groundhog' 
[ros2_control_node-1] [INFO] [1690518688.077200321] [resource_manager]: Initialize hardware 'groundhog' 
[ros2_control_node-1] [INFO] [1690518688.077387200] [groundhog_interface]: Registering hardware interface 'groundhog'
[ros2_control_node-1] [INFO] [1690518688.077420487] [groundhog_interface]: 'groundhog' has bus config: '/home/jerome/gh_ws/install/groundhog_canopen/share/groundhog_canopen/config/bus_one/bus.yml'
[ros2_control_node-1] [INFO] [1690518688.077424749] [groundhog_interface]: 'groundhog' has master config: '/home/jerome/gh_ws/install/groundhog_canopen/share/groundhog_canopen/config/bus_one/master.dcf'
[ros2_control_node-1] [INFO] [1690518688.077431023] [groundhog_interface]: 'groundhog' has master bin: ''
[ros2_control_node-1] [INFO] [1690518688.077433573] [groundhog_interface]: 'groundhog' has can interface: 'can0'
[ros2_control_node-1] [ERROR] [1690518688.078927651] [fr_drive_joint]: Node id for 'fr_drive_joint' is '3'
[ros2_control_node-1] [INFO] [1690518688.078958794] [fr_drive_joint]: Registered position_mode '1' for 'fr_drive_joint'
[ros2_control_node-1] [ERROR] [1690518688.079476299] [fl_drive_joint]: Node id for 'fl_drive_joint' is '2'
[ros2_control_node-1] [INFO] [1690518688.079495308] [fl_drive_joint]: Registered position_mode '1' for 'fl_drive_joint'
[ros2_control_node-1] [ERROR] [1690518688.079910619] [rl_drive_joint]: Node id for 'rl_drive_joint' is '4'
[ros2_control_node-1] [INFO] [1690518688.079921885] [rl_drive_joint]: Registered position_mode '1' for 'rl_drive_joint'
[ros2_control_node-1] [ERROR] [1690518688.080395877] [rr_drive_joint]: Node id for 'rr_drive_joint' is '5'
[ros2_control_node-1] [INFO] [1690518688.080408842] [rr_drive_joint]: Registered position_mode '1' for 'rr_drive_joint'
[ros2_control_node-1] [ERROR] [1690518688.080855163] [fl_steer_joint]: Node id for 'fl_steer_joint' is '6'
[ros2_control_node-1] [INFO] [1690518688.080866064] [fl_steer_joint]: Registered position_mode '1' for 'fl_steer_joint'
[ros2_control_node-1] [ERROR] [1690518688.081308383] [fr_steer_joint]: Node id for 'fr_steer_joint' is '7'
[ros2_control_node-1] [INFO] [1690518688.081318412] [fr_steer_joint]: Registered position_mode '1' for 'fr_steer_joint'
[ros2_control_node-1] [ERROR] [1690518688.081734641] [rl_steer_joint]: Node id for 'rl_steer_joint' is '8'
[ros2_control_node-1] [INFO] [1690518688.081744520] [rl_steer_joint]: Registered position_mode '1' for 'rl_steer_joint'
[ros2_control_node-1] [ERROR] [1690518688.082163511] [rr_steer_joint]: Node id for 'rr_steer_joint' is '9'
[ros2_control_node-1] [INFO] [1690518688.082177187] [rr_steer_joint]: Registered position_mode '1' for 'rr_steer_joint'
[ros2_control_node-1] [INFO] [1690518688.082284756] [resource_manager]: Successful initialization of hardware 'groundhog'
[ros2_control_node-1] [INFO] [1690518688.082507454] [resource_manager]: 'configure' hardware 'groundhog' 
[ros2_control_node-1] [INFO] [1690518688.088459229] [device_container]: Starting Device Container with:
[ros2_control_node-1] [INFO] [1690518688.088557863] [device_container]:          can_interface_name can0
[ros2_control_node-1] [INFO] [1690518688.088564271] [device_container]:          master_config /home/jerome/gh_ws/install/groundhog_canopen/share/groundhog_canopen/config/bus_one/master.dcf
[ros2_control_node-1] [INFO] [1690518688.088568871] [device_container]:          bus_config /home/jerome/gh_ws/install/groundhog_canopen/share/groundhog_canopen/config/bus_one/bus.yml
[ros2_control_node-1] [INFO] [1690518688.089502187] [device_container]: Loading Master Configuration.
[ros2_control_node-1] [INFO] [1690518688.089998120] [device_container]: Load Library: /home/jerome/gh_ws/install/canopen_master_driver/lib/libmaster_driver.so
[ros2_control_node-1] [INFO] [1690518688.091556908] [device_container]: Found class: rclcpp_components::NodeFactoryTemplate<ros2_canopen::MasterDriver>
[ros2_control_node-1] [INFO] [1690518688.091593304] [device_container]: Instantiate class: rclcpp_components::NodeFactoryTemplate<ros2_canopen::MasterDriver>
[ros2_control_node-1] [INFO] [1690518688.094374437] [master]: NodeCanopenBasicMaster
[ros2_control_node-1] [INFO] [1690518688.094474025] [device_container]: Load master component.
[ros2_control_node-1] [INFO] [1690518688.094603413] [device_container]: Added /master to executor
[ros2_control_node-1] [INFO] [1690518688.110590486] [device_container]: Loading Driver Configuration.
[ros2_control_node-1] [INFO] [1690518688.110718222] [device_container]: Found device fl_drive_joint with driver ros2_canopen::Cia402Driver
[ros2_control_node-1] [INFO] [1690518688.111036746] [device_container]: Load Library: /home/jerome/gh_ws/install/canopen_402_driver/lib/libcia402_driver.so
[ros2_control_node-1] [INFO] [1690518688.111592211] [device_container]: Found class: rclcpp_components::NodeFactoryTemplate<ros2_canopen::Cia402Driver>
[ros2_control_node-1] [INFO] [1690518688.111603309] [device_container]: Instantiate class: rclcpp_components::NodeFactoryTemplate<ros2_canopen::Cia402Driver>
[ros2_control_node-1] [INFO] [1690518688.114367414] [device_container]: Load driver component.
[ros2_control_node-1] [INFO] [1690518688.114584512] [device_container]: Added /fl_drive_joint to executor
[ros2_control_node-1] [ERROR] [1690518688.125236865] [fl_drive_joint]: Could not polling from config, setting to true.
[ros2_control_node-1] [ERROR] [1690518688.125365567] [fl_drive_joint]: Could not read enable diagnostics from config, setting to false.
[ros2_control_node-1] [INFO] [1690518688.125485531] [fl_drive_joint]: scale_pos_to_dev_ 1000.000000
[ros2_control_node-1] scale_pos_from_dev_ 0.001000
[ros2_control_node-1] scale_vel_to_dev_ 1000.000000
[ros2_control_node-1] scale_vel_from_dev_ 0.001000
[ros2_control_node-1] 
[ros2_control_node-1] [INFO] [1690518688.127016869] [fl_drive_joint]: eds file /home/jerome/gh_ws/install/groundhog_canopen/share/groundhog_canopen/config/bus_one/roboteq_motor_controllers_v80.eds
[ros2_control_node-1] [INFO] [1690518688.127039564] [fl_drive_joint]: bin file /home/jerome/gh_ws/install/groundhog_canopen/share/groundhog_canopen/config/bus_one/fl_drive_joint.bin
[ros2_control_node-1] Found rpdo mapped object: index=6040 subindex=0
[ros2_control_node-1] Found rpdo mapped object: index=6060 subindex=0
[ros2_control_node-1] Found rpdo mapped object: index=607a subindex=0
[ros2_control_node-1] Found rpdo mapped object: index=2005 subindex=c
[ros2_control_node-1] Found rpdo mapped object: index=2005 subindex=d
[ros2_control_node-1] Found rpdo mapped object: index=2005 subindex=e
[ros2_control_node-1] Found rpdo mapped object: index=2005 subindex=f
[ros2_control_node-1] Found rpdo mapped object: index=2005 subindex=10
[ros2_control_node-1] Found tpdo mapped object: index=6041 subindex=0
[ros2_control_node-1] Found tpdo mapped object: index=6061 subindex=0
[ros2_control_node-1] Found tpdo mapped object: index=6064 subindex=0
[ros2_control_node-1] Found tpdo mapped object: index=606c subindex=0
[ros2_control_node-1] Found tpdo mapped object: index=2106 subindex=5
[ros2_control_node-1] Found tpdo mapped object: index=2106 subindex=6
[ros2_control_node-1] Found tpdo mapped object: index=2106 subindex=7
[ros2_control_node-1] Found tpdo mapped object: index=2106 subindex=8
[ros2_control_node-1] [WARN] [1690518688.134979166] [fl_drive_joint]: Wait for device to boot.
[spawner-3] [INFO] [1690518690.097954863] [spawner_joint_state_broadcaster]: Waiting for '/controller_manager' services to be available
[spawner-4] [INFO] [1690518690.104051410] [spawner_forward_position_controller]: Waiting for '/controller_manager' services to be available
[spawner-3] [INFO] [1690518692.111551998] [spawner_joint_state_broadcaster]: Waiting for '/controller_manager' services to be available
[spawner-4] [INFO] [1690518692.116357703] [spawner_forward_position_controller]: Waiting for '/controller_manager' services to be available
[spawner-3] [INFO] [1690518694.123516338] [spawner_joint_state_broadcaster]: Waiting for '/controller_manager' services to be available
[spawner-4] [INFO] [1690518694.126392131] [spawner_forward_position_controller]: Waiting for '/controller_manager' services to be available
[spawner-3] [INFO] [1690518696.135869520] [spawner_joint_state_broadcaster]: Waiting for '/controller_manager' services to be available
[spawner-4] [INFO] [1690518696.137622356] [spawner_forward_position_controller]: Waiting for '/controller_manager' services to be available
[spawner-3] [ERROR] [1690518698.147600590] [spawner_joint_state_broadcaster]: Controller manager not available
[spawner-4] [ERROR] [1690518698.148850366] [spawner_forward_position_controller]: Controller manager not available
[ERROR] [spawner-3]: process has died [pid 164101, exit code 1, cmd '/opt/ros/humble/lib/controller_manager/spawner joint_state_broadcaster --controller-manager /controller_manager --ros-args'].
[ERROR] [spawner-4]: process has died [pid 164103, exit code 1, cmd '/opt/ros/humble/lib/controller_manager/spawner forward_position_controller --controller-manager /controller_manager --ros-args'].

Here is my launch file

from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.actions import OpaqueFunction
from launch.substitutions import (
    Command,
    FindExecutable,
    LaunchConfiguration,
    PathJoinSubstitution,
)
from launch_ros.actions import Node
from launch_ros.substitutions import FindPackageShare
from launch.actions import IncludeLaunchDescription
from launch.launch_description_sources import PythonLaunchDescriptionSource

from launch.actions import IncludeLaunchDescription
from launch.launch_description_sources import PythonLaunchDescriptionSource

def launch_setup(context, *args, **kwargs):

    name = LaunchConfiguration("name")
    prefix = LaunchConfiguration("prefix")

    # bus configuration
    bus_config_package = LaunchConfiguration("bus_config_package")
    bus_config_directory = LaunchConfiguration("bus_config_directory")
    bus_config_file = LaunchConfiguration("bus_config_file")
    # bus configuration file full path
    bus_config = PathJoinSubstitution(
        [FindPackageShare(bus_config_package), bus_config_directory, bus_config_file]
    )

    # master configuration
    master_config_package = LaunchConfiguration("master_config_package")
    master_config_directory = LaunchConfiguration("master_config_directory")
    master_config_file = LaunchConfiguration("master_config_file")
    # master configuration file full path
    master_config = PathJoinSubstitution(
        [
            FindPackageShare(master_config_package),
            master_config_directory,
            master_config_file,
        ]
    )

    # can interface name
    can_interface_name = LaunchConfiguration("can_interface_name")

    # Simulation or not
    is_sim = LaunchConfiguration("is_sim")

    master_bin_directory = LaunchConfiguration("master_bin_directory")
    # master_bin = PathJoinSubstitution(
    #     [
    #         FindPackageShare(master_config_package),
    #         master_bin_directory,
    #         "master.bin",
    #     ]
    # )

    master_bin = ""

    # robot description stuff
    description_package = LaunchConfiguration("description_package")
    description_file = LaunchConfiguration("description_file")
    robot_description_content = Command(
        [
            PathJoinSubstitution([FindExecutable(name="xacro")]),
            " ",
            PathJoinSubstitution(
                [FindPackageShare(description_package), "urdf", description_file]
            ),
            " ",
            "name:=",
            name,
            " ",
            "prefix:=",
            prefix,
            " ",
            "bus_config:=",
            bus_config,
            " ",
            "master_config:=",
            master_config,
            " ",
            "master_bin:=",
            master_bin,
            " ",
            "can_interface_name:=",
            can_interface_name,
            " ",
            "is_sim:=",
            is_sim,
            " ",
        ]
    )
    robot_description = {"robot_description": robot_description_content}

    # ros2 control configuration
    ros2_control_config_package = LaunchConfiguration("ros2_control_config_package")
    ros2_control_config_directory = LaunchConfiguration("ros2_control_config_directory")
    ros2_control_config_file = LaunchConfiguration("ros2_control_config_file")
    # ros2 control configuration file full path
    ros2_control_config = PathJoinSubstitution(
        [
            FindPackageShare(ros2_control_config_package),
            ros2_control_config_directory,
            ros2_control_config_file,
        ]
    )

    # nodes to start are listed below
    control_node = Node(
        package="controller_manager",
        executable="ros2_control_node",
        parameters=[robot_description, ros2_control_config],
        output="screen",
    )

    # load one controller just to make sure it can connect to controller_manager
    joint_state_broadcaster_spawner = Node(
        package="controller_manager",
        executable="spawner",
        arguments=[
            "joint_state_broadcaster",
            "--controller-manager",
            "/controller_manager",
        ],
    )

    forward_position_controller = Node(
        package="controller_manager",
        executable="spawner",
        arguments=[
            "forward_position_controller",
            "--controller-manager",
            "/controller_manager",
        ],
    )

    robot_state_publisher_node = Node(
        package="robot_state_publisher",
        executable="robot_state_publisher",
        output="both",
        parameters=[robot_description],
    )  # Launch one instance motor controller can node instead of the above

    nodes_to_start = [
        control_node,
        robot_state_publisher_node,
        joint_state_broadcaster_spawner,
        forward_position_controller,
    ]

    return nodes_to_start

def generate_launch_description():

    declared_arguments = []

    declared_arguments.append(
        DeclareLaunchArgument(
            "name", description="robot name", default_value="groundhog"
        )
    )

    declared_arguments.append(
        DeclareLaunchArgument("prefix", description="Prefix.", default_value="")
    )

    declared_arguments.append(
        DeclareLaunchArgument(
            "description_package",
            description="Package where urdf file is stored.",
            default_value="groundhog_description",
        )
    )

    declared_arguments.append(
        DeclareLaunchArgument(
            "description_file",
            description="Name of the urdf file.",
            default_value="groundhog.urdf.xacro",
        )
    )
    declared_arguments.append(
        DeclareLaunchArgument(
            "ros2_control_config_package",
            default_value="groundhog_control",
            description="Path to ros2_control configuration.",
        )
    )
    declared_arguments.append(
        DeclareLaunchArgument(
            "ros2_control_config_directory",
            default_value="config",
            description="Path to ros2_control configuration.",
        )
    )
    declared_arguments.append(
        DeclareLaunchArgument(
            "ros2_control_config_file",
            default_value="groundhog_canopen_ros2_control.yaml",
            description="Path to ros2_control configuration.",
        )
    )
    declared_arguments.append(
        DeclareLaunchArgument(
            "bus_config_package",
            default_value="groundhog_canopen",
            description="Path to bus configuration.",
        )
    )
    declared_arguments.append(
        DeclareLaunchArgument(
            "bus_config_directory",
            default_value="config/bus_one",
            description="Path to bus configuration.",
        )
    )
    declared_arguments.append(
        DeclareLaunchArgument(
            "bus_config_file",
            default_value="bus.yml",
            description="Path to bus configuration.",
        )
    )
    declared_arguments.append(
        DeclareLaunchArgument(
            "master_config_package",
            default_value="groundhog_canopen",
            description="Path to master configuration file (*.dcf)",
        )
    )
    declared_arguments.append(
        DeclareLaunchArgument(
            "master_config_directory",
            default_value="config/bus_one",
            description="Path to master configuration file (*.dcf)",
        )
    )
    declared_arguments.append(
        DeclareLaunchArgument(
            "master_config_file",
            default_value="master.dcf",
            description="Path to master configuration file (*.dcf)",
        )
    )

    declared_arguments.append(
        DeclareLaunchArgument(
            "master_bin_directory",
            default_value="config/bus_two/master_bin",
            description="Path to master bin file",
        )
    )

    declared_arguments.append(
        DeclareLaunchArgument(
            "can_interface_name",
            default_value="can0",
            description="Interface name for can",
        )
    )

    declared_arguments.append(
        DeclareLaunchArgument(
            "is_sim",
            default_value="false",
            description="Simulation or not",
        )
    )

    return LaunchDescription(
        declared_arguments + [OpaqueFunction(function=launch_setup)]
    )

Here is my bus.yaml

options:
  dcf_path: "@BUS_CONFIG_PATH@"

master:
  node_id: 1
  driver: ros2_canopen::MasterDriver
  package: canopen_master_driver
  sync_period: 10000

defaults:
  dcf: "roboteq_motor_controllers_v80.eds"
  driver: "ros2_canopen::Cia402Driver"
  package: "canopen_402_driver"
  period: 10
  heartbeat_producer: 1000
  position_mode: 1
  sdo:
    - {index: 0x6081, sub_index: 0, value: 1000}
    - {index: 0x60C2, sub_index: 1, value: 10} # Interpolation time period at 10 ms matches the period.

  tpdo: # TPDO needed statusword, actual velocity, actual position, mode of operation
    1:
      enabled: true
      cob_id: "auto"
      transmission: 0x01
      mapping:
        - {index: 0x6041, sub_index: 0} # status word
        - {index: 0x6061, sub_index: 0} # mode of operation display
    2:
      enabled: true
      cob_id: "auto"
      transmission: 0x01
      mapping:
        - {index: 0x6064, sub_index: 0} # position actual value
        - {index: 0x606c, sub_index: 0} # velocity actual position
    3:
      enabled: false
    4:
      enabled: false

  rpdo: # RPDO needed controlword, target position, target velocity, mode of operation
    1:
      enabled: true
      cob_id: "auto"
      mapping:
      - {index: 0x6040, sub_index: 0} # controlword
      - {index: 0x6060, sub_index: 0} # mode of operation
    2:
      enabled: true
      cob_id: "auto"
      mapping:
      - {index: 0x607A, sub_index: 0} # target position

nodes:
  fl_drive_joint:
    node_id: 2
  fr_drive_joint:
    node_id: 3
  rl_drive_joint:
    node_id: 4
  rr_drive_joint:
    node_id: 5
  fl_steer_joint:
    node_id: 6
  fr_steer_joint:
    node_id: 7
  rl_steer_joint:
    node_id: 8
  rr_steer_joint:
    node_id: 9

Here is my controller.yaml

controller_manager:
  ros__parameters:
    update_rate: 100  # Hz

    joint_state_broadcaster:
      type: joint_state_broadcaster/JointStateBroadcaster

    forward_position_controller:
      type: forward_command_controller/ForwardCommandController

forward_position_controller:
  ros__parameters:
    joints:
      - fl_drive_joint,
      - fr_drive_joint,
      - rl_drive_joint,
      - rr_drive_joint,
      - fl_steer_joint,
      - fr_steer_joint,
      - rl_steer_joint,
      - rr_steer_joint,
    interface_name: position

Setup:

hellantos commented 1 year ago

From your explanations I understand, that only two devices are on the bus, but you have configured 8. The driver expects these to be available when starting the hardware interface. We can probably improve the error communication in this case.

The solution in your case would be to only add the devices to configuration, that are actually available on the bus. Basically, the driver waits for fl_drive to boot, which never happens. We should probably add a timeout to the wait for boot function.

jclinton830 commented 11 months ago

From your explanations I understand, that only two devices are on the bus, but you have configured 8. The driver expects these to be available when starting the hardware interface. We can probably improve the error communication in this case.

The solution in your case would be to only add the devices to the configuration, that are actually available on the bus. Basically, the driver waits for fl_drive to boot, which never happens. We should probably add a timeout to the wait for boot function.

I have commented out the devices that are not available and tried it and still get the same error.

I even tried running the cia402_system.launch.py with my roboteq controller which supports CIA402 and still get the same error. See below.

What I changed to run the cia402_system.launch.py

config/cia402_system/bus.yml
config/cia402_system/cia402_system.ros2_control.xacro
launch/cia402_system.launch.py
jerome@jjustin:~/gh_ws/src/groundhog/scripts$ ros2 launch canopen_tests cia402_system.launch.py 
[INFO] [launch]: All log files can be found below /home/jerome/.ros/log/2023-08-17-09-47-03-462751-jjustin-10854
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [ros2_control_node-1]: process started with pid [10857]
[INFO] [robot_state_publisher-2]: process started with pid [10859]
[INFO] [spawner-3]: process started with pid [10861]
[INFO] [spawner-4]: process started with pid [10863]
[INFO] [spawner-5]: process started with pid [10865]
[robot_state_publisher-2] [INFO] [1692229623.701360938] [robot_state_publisher]: got segment base_link
[robot_state_publisher-2] [INFO] [1692229623.701454609] [robot_state_publisher]: got segment node_1_link
[ros2_control_node-1] [INFO] [1692229623.708501027] [resource_manager]: Loading hardware 'canopen_test_system' 
[ros2_control_node-1] [INFO] [1692229623.719788369] [resource_manager]: Initialize hardware 'canopen_test_system' 
[ros2_control_node-1] [INFO] [1692229623.720081733] [CanopenSystem]: bus_config: '/home/jerome/gh_ws/install/canopen_tests/share/canopen_tests/config/cia402_system/bus.yml'
[ros2_control_node-1] [INFO] [1692229623.720092544] [CanopenSystem]: master_config: '/home/jerome/gh_ws/install/canopen_tests/share/canopen_tests/config/cia402_system/master.dcf'
[ros2_control_node-1] [INFO] [1692229623.720097679] [CanopenSystem]: can_interface_name: 'can0'
[ros2_control_node-1] [INFO] [1692229623.720102391] [CanopenSystem]: master_bin: '""'
[ros2_control_node-1] [INFO] [1692229623.720111319] [resource_manager]: Successful initialization of hardware 'canopen_test_system'
[ros2_control_node-1] [INFO] [1692229623.720494593] [resource_manager]: 'configure' hardware 'canopen_test_system' 
[ros2_control_node-1] [INFO] [1692229624.326328886] [device_container]: Starting Device Container with:
[ros2_control_node-1] [INFO] [1692229624.326413604] [device_container]:          can_interface_name can0
[ros2_control_node-1] [INFO] [1692229624.326425156] [device_container]:          master_config /home/jerome/gh_ws/install/canopen_tests/share/canopen_tests/config/cia402_system/master.dcf
[ros2_control_node-1] [INFO] [1692229624.326434315] [device_container]:          bus_config /home/jerome/gh_ws/install/canopen_tests/share/canopen_tests/config/cia402_system/bus.yml
[ros2_control_node-1] [INFO] [1692229624.327557129] [device_container]: Loading Master Configuration.
[ros2_control_node-1] [INFO] [1692229624.328243568] [device_container]: Load Library: /home/jerome/gh_ws/install/canopen_master_driver/lib/libmaster_driver.so
[ros2_control_node-1] [INFO] [1692229624.330267545] [device_container]: Found class: rclcpp_components::NodeFactoryTemplate<ros2_canopen::MasterDriver>
[ros2_control_node-1] [INFO] [1692229624.330303941] [device_container]: Instantiate class: rclcpp_components::NodeFactoryTemplate<ros2_canopen::MasterDriver>
[ros2_control_node-1] [INFO] [1692229624.335210865] [master]: NodeCanopenBasicMaster
[ros2_control_node-1] [INFO] [1692229624.335392561] [device_container]: Load master component.
[ros2_control_node-1] [INFO] [1692229624.335570644] [device_container]: Added /master to executor
[ros2_control_node-1] [INFO] [1692229624.369374054] [device_container]: Loading Driver Configuration.
[ros2_control_node-1] [INFO] [1692229624.369495539] [device_container]: Found device cia402_device_1 with driver ros2_canopen::Cia402Driver
[ros2_control_node-1] [INFO] [1692229624.369908249] [device_container]: Load Library: /home/jerome/gh_ws/install/canopen_402_driver/lib/libcia402_driver.so
[ros2_control_node-1] [INFO] [1692229624.371326401] [device_container]: Found class: rclcpp_components::NodeFactoryTemplate<ros2_canopen::Cia402Driver>
[ros2_control_node-1] [INFO] [1692229624.371341666] [device_container]: Instantiate class: rclcpp_components::NodeFactoryTemplate<ros2_canopen::Cia402Driver>
[ros2_control_node-1] [INFO] [1692229624.377739774] [device_container]: Load driver component.
[ros2_control_node-1] [INFO] [1692229624.378012393] [device_container]: Added /cia402_device_1 to executor
[ros2_control_node-1] [ERROR] [1692229624.390987328] [cia402_device_1]: Could not polling from config, setting to true.
[ros2_control_node-1] [ERROR] [1692229624.391219464] [cia402_device_1]: Could not read enable diagnostics from config, setting to false.
[ros2_control_node-1] [INFO] [1692229624.391700961] [cia402_device_1]: scale_pos_to_dev_ 1000.000000
[ros2_control_node-1] scale_pos_from_dev_ 0.001000
[ros2_control_node-1] scale_vel_to_dev_ 1000.000000
[ros2_control_node-1] scale_vel_from_dev_ 0.001000
[ros2_control_node-1] 
[ros2_control_node-1] [INFO] [1692229624.393705059] [cia402_device_1]: eds file /home/jerome/gh_ws/install/canopen_tests/share/canopen_tests/config/cia402_system/roboteq_motor_controllers_v80.eds
[ros2_control_node-1] [INFO] [1692229624.393743855] [cia402_device_1]: bin file /home/jerome/gh_ws/install/canopen_tests/share/canopen_tests/config/cia402_system/cia402_device_1.bin
[ros2_control_node-1] Found rpdo mapped object: index=6040 subindex=0
[ros2_control_node-1] Found rpdo mapped object: index=6060 subindex=0
[ros2_control_node-1] Found rpdo mapped object: index=607a subindex=0
[ros2_control_node-1] Found rpdo mapped object: index=60ff subindex=0
[ros2_control_node-1] Found rpdo mapped object: index=2005 subindex=d
[ros2_control_node-1] Found rpdo mapped object: index=2005 subindex=e
[ros2_control_node-1] Found rpdo mapped object: index=2005 subindex=f
[ros2_control_node-1] Found rpdo mapped object: index=2005 subindex=10
[ros2_control_node-1] Found tpdo mapped object: index=6041 subindex=0
[ros2_control_node-1] Found tpdo mapped object: index=6061 subindex=0
[ros2_control_node-1] Found tpdo mapped object: index=6064 subindex=0
[ros2_control_node-1] Found tpdo mapped object: index=606c subindex=0
[ros2_control_node-1] Found tpdo mapped object: index=2106 subindex=5
[ros2_control_node-1] Found tpdo mapped object: index=2106 subindex=6
[ros2_control_node-1] Found tpdo mapped object: index=2106 subindex=7
[ros2_control_node-1] Found tpdo mapped object: index=2106 subindex=8
[ros2_control_node-1] [WARN] [1692229624.402508209] [cia402_device_1]: Wait for device to boot.
[spawner-3] [INFO] [1692229626.535245785] [spawner_joint_state_broadcaster]: Waiting for '/controller_manager' services to be available
[spawner-4] [INFO] [1692229626.577057051] [spawner_cia402_device_1_controller]: Waiting for '/controller_manager' services to be available
[spawner-5] [INFO] [1692229626.657432204] [spawner_forward_position_controller]: Waiting for '/controller_manager' services to be available
[spawner-3] [INFO] [1692229628.554354120] [spawner_joint_state_broadcaster]: Waiting for '/controller_manager' services to be available
[spawner-4] [INFO] [1692229628.595812310] [spawner_cia402_device_1_controller]: Waiting for '/controller_manager' services to be available
[spawner-5] [INFO] [1692229628.673832689] [spawner_forward_position_controller]: Waiting for '/controller_manager' services to be available
[spawner-3] [INFO] [1692229630.571280539] [spawner_joint_state_broadcaster]: Waiting for '/controller_manager' services to be available
[spawner-4] [INFO] [1692229630.611718035] [spawner_cia402_device_1_controller]: Waiting for '/controller_manager' services to be available
[spawner-5] [INFO] [1692229630.689001376] [spawner_forward_position_controller]: Waiting for '/controller_manager' services to be available
[spawner-3] [INFO] [1692229632.585920661] [spawner_joint_state_broadcaster]: Waiting for '/controller_manager' services to be available
[spawner-4] [INFO] [1692229632.625720892] [spawner_cia402_device_1_controller]: Waiting for '/controller_manager' services to be available
[spawner-5] [INFO] [1692229632.705058881] [spawner_forward_position_controller]: Waiting for '/controller_manager' services to be available
[spawner-3] [ERROR] [1692229634.601373717] [spawner_joint_state_broadcaster]: Controller manager not available
[spawner-4] [ERROR] [1692229634.639810551] [spawner_cia402_device_1_controller]: Controller manager not available
[spawner-5] [ERROR] [1692229634.720709995] [spawner_forward_position_controller]: Controller manager not available
[ERROR] [spawner-3]: process has died [pid 10861, exit code 1, cmd '/opt/ros/humble/lib/controller_manager/spawner joint_state_broadcaster --controller-manager /controller_manager --ros-args'].
[ERROR] [spawner-4]: process has died [pid 10863, exit code 1, cmd '/opt/ros/humble/lib/controller_manager/spawner cia402_device_1_controller --controller-manager /controller_manager --ros-args'].
[ERROR] [spawner-5]: process has died [pid 10865, exit code 1, cmd '/opt/ros/humble/lib/controller_manager/spawner forward_position_controller --controller-manager /controller_manager --ros-args'].
hellantos commented 11 months ago

@jclinton830 can you as well provide the candump for this?

jclinton830 commented 11 months ago

@ipa-cmh see below

can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  70C   [1]  05
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  70C   [1]  05
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  70C   [1]  05
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  70C   [1]  05
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  70C   [1]  05
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  70C   [1]  05
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  70C   [1]  05
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  70C   [1]  05
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  70C   [1]  05
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  70C   [1]  05
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  701   [1]  00
  can0  000   [2]  82 00
  can0  70C   [1]  00
  can0  60C   [8]  40 00 10 00 00 00 00 00
  can0  08C   [8]  00 00 00 00 00 00 00 00
  can0  58C   [8]  43 00 10 00 91 01 0F 00
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  70C   [1]  7F
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  70C   [1]  7F
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  70C   [1]  7F
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
hellantos commented 11 months ago

@jclinton830 There could be two reasons for this behavior.

  1. The device type in eds does not match the one on the device (index: 0x1000 value: 91 01 0F 00).
  2. We receive an EMCY message from the device that might break the configuration (0x8C 00 00 00 00 00 00 00 00). Though the EMCY message itself indicates there is no error on the device.

I will check how the EMCY situation could be caused.

jclinton830 commented 11 months ago

Thanks for getting back to me @ipa-cmh.

That is strange that the device type does not match the eds. I got the EDS directly from the Robotech website. It is called CANOPEN EDS for motor controllers found here https://www.roboteq.com/support/files-download

They seem to only have one EDS for all their CANOpen-enabled motor controllers.

Your help here would be greatly appreciated. Let me know if you need any other information.

jclinton830 commented 11 months ago

@ipa-cmh any updates on this from your side?

hellantos commented 11 months ago

@jclinton830 can you do an experiment for me.? Please use consend tool to send the following to your device?

000 82 00
60C 40 00 10 00 00 00 00 00

And record results with candump?

jclinton830 commented 11 months ago

@ipa-cmh See below.

CANSEND:

jerome@jjustin:~$ cansend can0 000#8200
jerome@jjustin:~$ cansend can0 60c#4000100000000000

CANDUMP :

jerome@jjustin:~/gh_ws/src/groundhog/scripts$ candump can0
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  38C   [8]  00 00 00 00 00 00 00 00
  can0  48C   [8]  00 00 00 00 00 00 00 00
  can0  70C   [1]  05
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  70C   [1]  05
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  70C   [1]  05
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  70C   [1]  05
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  70C   [1]  05
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  70C   [1]  05
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  70C   [1]  05
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  70C   [1]  05
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  70C   [1]  05
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  70C   [1]  05
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  70C   [1]  05
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  70C   [1]  05
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  70C   [1]  05
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  70C   [1]  05
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  70C   [1]  05
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  70C   [1]  05
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  70C   [1]  05
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  70C   [1]  05
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  70C   [1]  05
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  70C   [1]  05
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  70C   [1]  05
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  70C   [1]  05
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  70C   [1]  05
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  70C   [1]  05
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  000   [2]  82 00
  can0  70C   [1]  00
  can0  08C   [8]  00 00 00 00 00 00 00 00
  can0  70C   [1]  7F
  can0  70C   [1]  7F
  can0  70C   [1]  7F
  can0  70C   [1]  7F
  can0  70C   [1]  7F
  can0  70C   [1]  7F
  can0  70C   [1]  7F
  can0  70C   [1]  7F
  can0  70C   [1]  7F
  can0  70C   [1]  7F
  can0  60C   [8]  40 00 10 00 00 00 00 00
  can0  58C   [8]  43 00 10 00 91 01 0F 00
  can0  70C   [1]  7F
  can0  70C   [1]  7F
  can0  70C   [1]  7F
  can0  70C   [1]  7F
  can0  70C   [1]  7F
  can0  70C   [1]  7F
  can0  70C   [1]  7F
  can0  70C   [1]  7F
  can0  70C   [1]  7F
  can0  70C   [1]  7F
  can0  70C   [1]  7F
  can0  70C   [1]  7F
  can0  70C   [1]  7F

Have you got a hunch yet?

jclinton830 commented 11 months ago

Today I did another test by modifying the cia402_setup.launch.py to see if the cia402_driver is working with my roboteq controller. Here is the output, and it seems to hang at at wait for device to boot.

jerome@jjustin:~/gh_ws$ ros2 launch canopen_tests cia402_setup.launch.py 
[INFO] [launch]: All log files can be found below /home/jerome/.ros/log/2023-09-04-12-00-54-282326-jjustin-344925
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [launch.user]: /home/jerome/gh_ws/install/canopen_tests/share/canopen_tests/config/cia402/bus.yml
[INFO] [launch.user]: /home/jerome/gh_ws/install/canopen_tests/share/canopen_tests/config/cia402/master.dcf
[INFO] [launch.user]: 
[INFO] [launch.user]: can0
[INFO] [device_container_node-1]: process started with pid [344945]
[device_container_node-1] [INFO] [1693792855.454155015] [device_container_node]: Starting Device Container with:
[device_container_node-1] [INFO] [1693792855.454233516] [device_container_node]:         master_config /home/jerome/gh_ws/install/canopen_tests/share/canopen_tests/config/cia402/master.dcf
[device_container_node-1] [INFO] [1693792855.454239017] [device_container_node]:         bus_config /home/jerome/gh_ws/install/canopen_tests/share/canopen_tests/config/cia402/bus.yml
[device_container_node-1] [INFO] [1693792855.454242179] [device_container_node]:         can_interface_name can0
[device_container_node-1] [INFO] [1693792855.454805252] [device_container_node]: Loading Master Configuration.
[device_container_node-1] [INFO] [1693792855.455117289] [device_container_node]: Load Library: /home/jerome/gh_ws/install/canopen_master_driver/lib/libmaster_driver.so
[device_container_node-1] [INFO] [1693792855.457121558] [device_container_node]: Found class: rclcpp_components::NodeFactoryTemplate<ros2_canopen::MasterDriver>
[device_container_node-1] [INFO] [1693792855.457135435] [device_container_node]: Instantiate class: rclcpp_components::NodeFactoryTemplate<ros2_canopen::MasterDriver>
[device_container_node-1] [INFO] [1693792856.494835657] [master]: NodeCanopenBasicMaster
[device_container_node-1] [INFO] [1693792856.494968774] [device_container_node]: Load master component.
[device_container_node-1] [INFO] [1693792856.495045771] [device_container_node]: Added /master to executor
[device_container_node-1] [INFO] [1693792856.505281373] [device_container_node]: Loading Driver Configuration.
[device_container_node-1] [INFO] [1693792856.505371170] [device_container_node]: Found device cia402_device_1 with driver ros2_canopen::Cia402Driver
[device_container_node-1] [INFO] [1693792856.505638632] [device_container_node]: Load Library: /home/jerome/gh_ws/install/canopen_402_driver/lib/libcia402_driver.so
[device_container_node-1] [INFO] [1693792856.510131711] [device_container_node]: Found class: rclcpp_components::NodeFactoryTemplate<ros2_canopen::Cia402Driver>
[device_container_node-1] [INFO] [1693792856.510165086] [device_container_node]: Instantiate class: rclcpp_components::NodeFactoryTemplate<ros2_canopen::Cia402Driver>
[device_container_node-1] [INFO] [1693792856.514515255] [device_container_node]: Load driver component.
[device_container_node-1] [INFO] [1693792856.514631289] [device_container_node]: Added /cia402_device_1 to executor
[device_container_node-1] [ERROR] [1693792856.526726597] [cia402_device_1]: Could not polling from config, setting to true.
[device_container_node-1] [ERROR] [1693792856.526870727] [cia402_device_1]: Could not read enable diagnostics from config, setting to false.
[device_container_node-1] [INFO] [1693792856.527005934] [cia402_device_1]: scale_pos_to_dev_ 1000.000000
[device_container_node-1] scale_pos_from_dev_ 0.001000
[device_container_node-1] scale_vel_to_dev_ 1000.000000
[device_container_node-1] scale_vel_from_dev_ 0.001000
[device_container_node-1] 
[device_container_node-1] [INFO] [1693792856.528226164] [cia402_device_1]: eds file /home/jerome/gh_ws/install/canopen_tests/share/canopen_tests/config/cia402/roboteq_motor_controllers_v80.eds
[device_container_node-1] [INFO] [1693792856.528250019] [cia402_device_1]: bin file /home/jerome/gh_ws/install/canopen_tests/share/canopen_tests/config/cia402/cia402_device_1.bin
[device_container_node-1] Found rpdo mapped object: index=6040 subindex=0
[device_container_node-1] Found rpdo mapped object: index=6060 subindex=0
[device_container_node-1] Found rpdo mapped object: index=607a subindex=0
[device_container_node-1] Found rpdo mapped object: index=60ff subindex=0
[device_container_node-1] Found rpdo mapped object: index=2005 subindex=d
[device_container_node-1] Found rpdo mapped object: index=2005 subindex=e
[device_container_node-1] Found rpdo mapped object: index=2005 subindex=f
[device_container_node-1] Found rpdo mapped object: index=2005 subindex=10
[device_container_node-1] Found tpdo mapped object: index=6041 subindex=0
[device_container_node-1] Found tpdo mapped object: index=6061 subindex=0
[device_container_node-1] Found tpdo mapped object: index=6064 subindex=0
[device_container_node-1] Found tpdo mapped object: index=606c subindex=0
[device_container_node-1] Found tpdo mapped object: index=2106 subindex=5
[device_container_node-1] Found tpdo mapped object: index=2106 subindex=6
[device_container_node-1] Found tpdo mapped object: index=2106 subindex=7
[device_container_node-1] Found tpdo mapped object: index=2106 subindex=8
[device_container_node-1] [WARN] [1693792856.535945470] [cia402_device_1]: Wait for device to boot.

Here is the modified launch file:

import os
from ament_index_python import get_package_share_directory
from launch import LaunchDescription
import launch
from launch.actions import IncludeLaunchDescription
from launch.launch_description_sources import PythonLaunchDescriptionSource

def generate_launch_description():
    master_bin_path = os.path.join(
        get_package_share_directory("canopen_tests"),
        "config",
        "cia402",
        "master.bin",
    )
    if not os.path.exists(master_bin_path):
        master_bin_path = ""
    device_container = IncludeLaunchDescription(
        PythonLaunchDescriptionSource(
            [
                os.path.join(get_package_share_directory("canopen_core"), "launch"),
                "/canopen.launch.py",
            ]
        ),
        launch_arguments={
            "master_config": os.path.join(
                get_package_share_directory("canopen_tests"),
                "config",
                "cia402",
                "master.dcf",
            ),
            "master_bin": master_bin_path,
            "bus_config": os.path.join(
                get_package_share_directory("canopen_tests"),
                "config",
                "cia402",
                "bus.yml",
            ),
            "can_interface_name": "can0",
        }.items(),
    )

    return LaunchDescription([device_container])

Here is the bus.yaml

options:
  dcf_path: "@BUS_CONFIG_PATH@"

master:
  node_id: 1
  driver: "ros2_canopen::MasterDriver"
  package: "canopen_master_driver"
  sync_period: 10000

defaults:
  dcf: "roboteq_motor_controllers_v80.eds"
  driver: "ros2_canopen::Cia402Driver"
  package: "canopen_402_driver"
  period: 10
  revision_number: 0
  sdo:
    - {index: 0x60C2, sub_index: 1, value: 50} # Set interpolation time for cyclic modes to 50 ms
    - {index: 0x60C2, sub_index: 2, value: -3} # Set base 10-3s
    - {index: 0x6081, sub_index: 0, value: 1000}
    - {index: 0x6083, sub_index: 0, value: 2000}
  tpdo: # TPDO needed statusword, actual velocity, actual position, mode of operation
    1:
      enabled: true
      cob_id: "auto"
      transmission: 0x01
      mapping:
        - {index: 0x6041, sub_index: 0} # status word
        - {index: 0x6061, sub_index: 0} # mode of operation display
    2:
      enabled: true
      cob_id: "auto"
      transmission: 0x01
      mapping:
        - {index: 0x6064, sub_index: 0} # position actual value
        - {index: 0x606c, sub_index: 0} # velocity actual position
    3:
      enabled: false
    4:
      enabled: false
  rpdo: # RPDO needed controlword, target position, target velocity, mode of operation
    1:
      enabled: true
      cob_id: "auto"
      mapping:
      - {index: 0x6040, sub_index: 0} # controlword
      - {index: 0x6060, sub_index: 0} # mode of operation
    2:
      enabled: true
      cob_id: "auto"
      mapping:
      - {index: 0x607A, sub_index: 0} # target position
      - {index: 0x60FF, sub_index: 0} # target velocity

nodes:
  cia402_device_1:
    node_id: 12

Here is the candump:

jerome@jjustin:~$ candump can0
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  70C   [1]  05
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  70C   [1]  05
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  70C   [1]  05
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  70C   [1]  05
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  70C   [1]  05
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  70C   [1]  05
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  70C   [1]  05
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  70C   [1]  05
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  70C   [1]  05
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  18C   [8]  00 00 00 00 00 00 00 00
  can0  28C   [8]  00 00 00 00 00 00 00 00
  can0  70C   [1]  05
  can0  701   [1]  00
  can0  000   [2]  82 00
  can0  080   [0] 
  can0  70C   [1]  00
  can0  60C   [8]  40 00 10 00 00 00 00 00
  can0  08C   [8]  00 00 00 00 00 00 00 00
  can0  58C   [8]  43 00 10 00 91 01 0F 00
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  70C   [1]  7F
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  70C   [1]  7F
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  70C   [1]  7F
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  70C   [1]  7F
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  70C   [1]  7F
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 

Here is the folder structure inside the config folder

jerome@jjustin:~/gh_ws/src/ros2_canopen/canopen_tests/config/cia402$ tree
.
├── bus.yml
├── cia402_slave.eds
└── roboteq_motor_controllers_v80.eds

0 directories, 3 files
hellantos commented 11 months ago

@jclinton830 It seems, that your device has a longer boot sequence an will go into error if we send config before receiving the following message.

can0  08C   [8]  00 00 00 00 00 00 00 00

I believe this could be fixed by adding a delay to the start of the configuration process. It will require a small PR, to make this possible. I will see if I can make the changes this week.

jclinton830 commented 11 months ago

@ipa-cmh thanks for the response.

Is it possible to make the delay parameter configurable in milliseconds format from the bus.yaml file?

Also, I am happy to test out the PR before merging it.

hellantos commented 11 months ago

@jclinton830 just a short status update. There is no setting for this in the underlying library and other than I believed, I am not able to delay the boot process by using existing callbacks.

The solution would be to make the master not automatically boot and then trigger the boot, configuration and start later with appropriate timing.

For now I would expose ROS services to trigger these actions. If we get more people with a similar issue, I'll check how we can make it configurable inside.

This would mean, you have to write a small node that calls the services before your devices are ready and configured.

I am still checking with maintainer of the core library gor other solutions.

jclinton830 commented 10 months ago

@ipa-cmh thank you for the update!

I was tinkering with it today and sort of got it to work. One thing I am doing differently now is as soon as the device boots up I issue an NMT command through cansend. cansend can0 000#8200 and then the rest seems to work. I tried this with the cia402_setup.launch, cia402_system.launch and got the driver to work with the roboteq controller. It boots with an issue - no matching device type found in 1000.

I then tested if the same procedure would work in my current project. Here is an attached video of my screen grab and the actual ros2 launch log below the vidwo. You can see that in the terminal on the bottom left, I am issuing the NMT command multiple times just after the boot up and before waiting for /controller_manager times out. I am issuing this multiple times because not sure at what point of the launch process it exactly works.

https://github.com/ros-industrial/ros2_canopen/assets/3524727/beb60107-f0ea-4479-b1b0-0f8f5d2a6d9e

jerome@jjustin:~/gh_ws$ ros2 launch groundhog_control canopen_system.launch.py 
[INFO] [launch]: All log files can be found below /home/jerome/.ros/log/2023-09-12-13-58-07-494755-jjustin-32227
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [ros2_control_node-1]: process started with pid [32235]
[INFO] [robot_state_publisher-2]: process started with pid [32237]
[INFO] [spawner-3]: process started with pid [32239]
[INFO] [spawner-4]: process started with pid [32241]
[robot_state_publisher-2] [WARN] [1694491087.995951706] [kdl_parser]: The root link base_link has an inertia specified in the URDF, but KDL does not support a root link with an inertia.  As a workaround, you can add an extra dummy link to your URDF.
[robot_state_publisher-2] [INFO] [1694491087.996051656] [robot_state_publisher]: got segment base_link
[robot_state_publisher-2] [INFO] [1694491087.996119486] [robot_state_publisher]: got segment fl_steer_link
[robot_state_publisher-2] [INFO] [1694491087.996125613] [robot_state_publisher]: got segment fl_wheel_link
[robot_state_publisher-2] [INFO] [1694491087.996130184] [robot_state_publisher]: got segment fr_steer_link
[robot_state_publisher-2] [INFO] [1694491087.996134770] [robot_state_publisher]: got segment fr_wheel_link
[robot_state_publisher-2] [INFO] [1694491087.996139308] [robot_state_publisher]: got segment rl_steer_link
[robot_state_publisher-2] [INFO] [1694491087.996143404] [robot_state_publisher]: got segment rl_wheel_link
[robot_state_publisher-2] [INFO] [1694491087.996147702] [robot_state_publisher]: got segment rr_steer_link
[robot_state_publisher-2] [INFO] [1694491087.996152160] [robot_state_publisher]: got segment rr_wheel_link
[ros2_control_node-1] [INFO] [1694491090.030123325] [resource_manager]: Loading hardware 'groundhog' 
[ros2_control_node-1] [INFO] [1694491090.052009125] [resource_manager]: Initialize hardware 'groundhog' 
[ros2_control_node-1] [INFO] [1694491090.055090026] [groundhog_interface]: Registering hardware interface 'groundhog'
[ros2_control_node-1] [INFO] [1694491090.056264608] [groundhog_interface]: 'groundhog' has bus config: '/home/jerome/gh_ws/install/groundhog_canopen/share/groundhog_canopen/config/bus_one/bus.yml'
[ros2_control_node-1] [INFO] [1694491090.056895907] [groundhog_interface]: 'groundhog' has master config: '/home/jerome/gh_ws/install/groundhog_canopen/share/groundhog_canopen/config/bus_one/master.dcf'
[ros2_control_node-1] [INFO] [1694491090.059324590] [groundhog_interface]: 'groundhog' has master bin: ''
[ros2_control_node-1] [INFO] [1694491090.059954378] [groundhog_interface]: 'groundhog' has can interface: 'can0'
[ros2_control_node-1] [ERROR] [1694491090.062118253] [fr_drive_joint]: Node id for 'fr_drive_joint' is '12'
[ros2_control_node-1] [INFO] [1694491090.062620543] [fr_drive_joint]: Registered position_mode '1' for 'fr_drive_joint'
[ros2_control_node-1] [INFO] [1694491090.064188689] [resource_manager]: Successful initialization of hardware 'groundhog'
[ros2_control_node-1] [INFO] [1694491090.065207361] [resource_manager]: 'configure' hardware 'groundhog' 
[ros2_control_node-1] [INFO] [1694491090.100511190] [device_container]: Starting Device Container with:
[ros2_control_node-1] [INFO] [1694491090.100655627] [device_container]:          can_interface_name can0
[ros2_control_node-1] [INFO] [1694491090.100662480] [device_container]:          master_config /home/jerome/gh_ws/install/groundhog_canopen/share/groundhog_canopen/config/bus_one/master.dcf
[ros2_control_node-1] [INFO] [1694491090.100667127] [device_container]:          bus_config /home/jerome/gh_ws/install/groundhog_canopen/share/groundhog_canopen/config/bus_one/bus.yml
[ros2_control_node-1] [INFO] [1694491090.101297402] [device_container]: Loading Master Configuration.
[ros2_control_node-1] [INFO] [1694491090.101913105] [device_container]: Load Library: /home/jerome/gh_ws/install/canopen_master_driver/lib/libmaster_driver.so
[ros2_control_node-1] [INFO] [1694491090.104627652] [device_container]: Found class: rclcpp_components::NodeFactoryTemplate<ros2_canopen::MasterDriver>
[ros2_control_node-1] [INFO] [1694491090.104701264] [device_container]: Instantiate class: rclcpp_components::NodeFactoryTemplate<ros2_canopen::MasterDriver>
[spawner-4] [INFO] [1694491090.811375142] [spawner_forward_position_controller]: Waiting for '/controller_manager' node to exist
[ros2_control_node-1] [INFO] [1694491090.850736246] [master]: NodeCanopenBasicMaster
[ros2_control_node-1] [INFO] [1694491090.850955347] [device_container]: Load master component.
[ros2_control_node-1] [INFO] [1694491090.851161543] [device_container]: Added /master to executor
[ros2_control_node-1] [INFO] [1694491090.899297233] [device_container]: Loading Driver Configuration.
[ros2_control_node-1] [INFO] [1694491090.899577181] [device_container]: Found device fr_drive_joint with driver ros2_canopen::Cia402Driver
[ros2_control_node-1] [INFO] [1694491090.900212151] [device_container]: Load Library: /home/jerome/gh_ws/install/canopen_402_driver/lib/libcia402_driver.so
[ros2_control_node-1] [INFO] [1694491090.901521642] [device_container]: Found class: rclcpp_components::NodeFactoryTemplate<ros2_canopen::Cia402Driver>
[ros2_control_node-1] [INFO] [1694491090.901558418] [device_container]: Instantiate class: rclcpp_components::NodeFactoryTemplate<ros2_canopen::Cia402Driver>
[ros2_control_node-1] [INFO] [1694491090.951109973] [device_container]: Load driver component.
[ros2_control_node-1] [INFO] [1694491090.951492689] [device_container]: Added /fr_drive_joint to executor
[ros2_control_node-1] [ERROR] [1694491090.998634203] [fr_drive_joint]: Could not polling from config, setting to true.
[ros2_control_node-1] [ERROR] [1694491090.999111060] [fr_drive_joint]: Could not read enable diagnostics from config, setting to false.
[ros2_control_node-1] [INFO] [1694491090.999527698] [fr_drive_joint]: scale_pos_to_dev_ 1000.000000
[ros2_control_node-1] scale_pos_from_dev_ 0.001000
[ros2_control_node-1] scale_vel_to_dev_ 1000.000000
[ros2_control_node-1] scale_vel_from_dev_ 0.001000
[ros2_control_node-1] 
[ros2_control_node-1] [INFO] [1694491091.005270033] [fr_drive_joint]: eds file /home/jerome/gh_ws/install/groundhog_canopen/share/groundhog_canopen/config/bus_one/roboteq_motor_controllers_v80.eds
[ros2_control_node-1] [INFO] [1694491091.005335855] [fr_drive_joint]: bin file /home/jerome/gh_ws/install/groundhog_canopen/share/groundhog_canopen/config/bus_one/fr_drive_joint.bin
[ros2_control_node-1] Found rpdo mapped object: index=6040 subindex=0
[ros2_control_node-1] Found rpdo mapped object: index=6060 subindex=0
[ros2_control_node-1] Found rpdo mapped object: index=607a subindex=0
[ros2_control_node-1] Found rpdo mapped object: index=2005 subindex=c
[ros2_control_node-1] Found rpdo mapped object: index=2005 subindex=d
[ros2_control_node-1] Found rpdo mapped object: index=2005 subindex=e
[ros2_control_node-1] Found rpdo mapped object: index=2005 subindex=f
[ros2_control_node-1] Found rpdo mapped object: index=2005 subindex=10
[ros2_control_node-1] Found tpdo mapped object: index=6041 subindex=0
[ros2_control_node-1] Found tpdo mapped object: index=6061 subindex=0
[ros2_control_node-1] Found tpdo mapped object: index=6064 subindex=0
[ros2_control_node-1] Found tpdo mapped object: index=606c subindex=0
[ros2_control_node-1] Found tpdo mapped object: index=2106 subindex=5
[ros2_control_node-1] Found tpdo mapped object: index=2106 subindex=6
[ros2_control_node-1] Found tpdo mapped object: index=2106 subindex=7
[ros2_control_node-1] Found tpdo mapped object: index=2106 subindex=8
[ros2_control_node-1] [WARN] [1694491091.041171760] [fr_drive_joint]: Wait for device to boot.
[ros2_control_node-1] [ERROR] [1694491092.008214713] [fr_drive_joint]: Boot Issue: Value of object 1000 from CANopen device is different to value in object 1F84 (Device type).
[ros2_control_node-1] [INFO] [1694491092.008278310] [fr_drive_joint]: Driver booted and ready.
[ros2_control_node-1] [INFO] [1694491092.008698843] [fr_drive_joint]: Starting with polling mode.
[ros2_control_node-1] [INFO] [1694491092.009772525] [device_container]: Initialisation successful.
[ros2_control_node-1] [INFO] [1694491092.010065256] [resource_manager]: Successful 'configure' of hardware 'groundhog'
[ros2_control_node-1] [WARN] [1694491092.010086127] [resource_manager]: (hardware 'groundhog'): 'fr_drive_joint/position' state interface already in available list. This can happen due to multiple calls to 'configure'
[ros2_control_node-1] [WARN] [1694491092.010092414] [resource_manager]: (hardware 'groundhog'): 'fr_drive_joint/velocity' state interface already in available list. This can happen due to multiple calls to 'configure'
[ros2_control_node-1] [WARN] [1694491092.010097572] [resource_manager]: (hardware 'groundhog'): 'fr_drive_joint/position' command interface already in available list. This can happen due to multiple calls to 'configure'
[ros2_control_node-1] [INFO] [1694491092.010101508] [resource_manager]: 'activate' hardware 'groundhog' 
[ros2_control_node-1] [ERROR] [1694491092.013203069] [fr_drive_joint]: AsyncUpload:0C:6502:00: General error (08000000): General error
[ros2_control_node-1] [ERROR] [1694491092.016016054] [fr_drive_joint]: AsyncUpload:0C:6502:00: General error (08000000): General error
[ros2_control_node-1] [ERROR] [1694491092.019053780] [fr_drive_joint]: AsyncUpload:0C:6502:00: General error (08000000): General error
[ros2_control_node-1] [INFO] [1694491092.019593273] [canopen_402_driver]: Fault reset
[ros2_control_node-1] [ERROR] [1694491092.022084351] [fr_drive_joint]: AsyncUpload:0C:6502:00: General error (08000000): General error
[ros2_control_node-1] [ERROR] [1694491092.025175428] [fr_drive_joint]: AsyncUpload:0C:6502:00: General error (08000000): General error
[ros2_control_node-1] [ERROR] [1694491092.029193229] [fr_drive_joint]: AsyncUpload:0C:6502:00: General error (08000000): General error
[ros2_control_node-1] [ERROR] [1694491092.033135229] [fr_drive_joint]: AsyncUpload:0C:6502:00: General error (08000000): General error
[ros2_control_node-1] [ERROR] [1694491092.036067014] [fr_drive_joint]: AsyncUpload:0C:6502:00: General error (08000000): General error
[ros2_control_node-1] [ERROR] [1694491092.040178715] [fr_drive_joint]: AsyncUpload:0C:6502:00: General error (08000000): General error
[ros2_control_node-1] [INFO] [1694491092.040380019] [canopen_402_driver]: Init: Read State
[ros2_control_node-1] [INFO] [1694491092.040420806] [canopen_402_driver]: Init: Enable
[ros2_control_node-1] [INFO] [1694491092.049297130] [canopen_402_driver]: Fault reset
[ros2_control_node-1] [INFO] [1694491092.307130595] [fr_drive_joint]: Slave 0xC: Switched NMT state to PREOP
[spawner-4] [INFO] [1694491092.821775923] [spawner_forward_position_controller]: Waiting for '/controller_manager' services to be available
[ros2_control_node-1] [INFO] [1694491093.192588138] [fr_drive_joint]: Slave 0xC: Switched NMT state to START
[ros2_control_node-1] [INFO] [1694491093.493506919] [fr_drive_joint]: Slave 0xC: Switched NMT state to PREOP
[spawner-3] [INFO] [1694491093.619373089] [spawner_joint_state_broadcaster]: Waiting for '/controller_manager' services to be available
[ros2_control_node-1] [INFO] [1694491094.565358955] [fr_drive_joint]: Slave 0xC: Switched NMT state to START
[spawner-4] [INFO] [1694491094.831476926] [spawner_forward_position_controller]: Waiting for '/controller_manager' services to be available
[ros2_control_node-1] [INFO] [1694491094.866401611] [fr_drive_joint]: Slave 0xC: Switched NMT state to PREOP
[spawner-3] [INFO] [1694491095.629525583] [spawner_joint_state_broadcaster]: Waiting for '/controller_manager' services to be available
[ros2_control_node-1] [INFO] [1694491095.813429538] [fr_drive_joint]: Slave 0xC: Switched NMT state to START
[ros2_control_node-1] [INFO] [1694491096.114545158] [fr_drive_joint]: Slave 0xC: Switched NMT state to PREOP
[spawner-4] [INFO] [1694491096.842369192] [spawner_forward_position_controller]: Waiting for '/controller_manager' services to be available
[ros2_control_node-1] [INFO] [1694491096.950664462] [fr_drive_joint]: Slave 0xC: Switched NMT state to START
[ros2_control_node-1] [INFO] [1694491097.040550857] [canopen_402_driver]: Transition timed out.
[ros2_control_node-1] [ERROR] [1694491097.040613006] [groundhog_interface]: Failed to activate 'fr_drive_joint'
[ros2_control_node-1] [INFO] [1694491097.040638500] [resource_manager]: Failed to 'activate' hardware 'groundhog'
[ros2_control_node-1] Could not enable motor
[ros2_control_node-1] [INFO] [1694491097.053689932] [controller_manager]: update rate is 100 Hz
[ros2_control_node-1] [INFO] [1694491097.054284997] [controller_manager]: RT kernel is recommended for better performance
[ros2_control_node-1] [INFO] [1694491097.248764167] [controller_manager]: Loading controller 'joint_state_broadcaster'
[ros2_control_node-1] [INFO] [1694491097.251690666] [fr_drive_joint]: Slave 0xC: Switched NMT state to PREOP
[spawner-3] [INFO] [1694491097.265788972] [spawner_joint_state_broadcaster]: Loaded joint_state_broadcaster
[ros2_control_node-1] [INFO] [1694491097.268097528] [controller_manager]: Loading controller 'forward_position_controller'
[ros2_control_node-1] [INFO] [1694491097.294873615] [controller_manager]: Configuring controller 'joint_state_broadcaster'
[ros2_control_node-1] [INFO] [1694491097.295004953] [joint_state_broadcaster]: 'joints' or 'interfaces' parameter is empty. All available state interfaces will be published
[spawner-4] [INFO] [1694491097.295523512] [spawner_forward_position_controller]: Loaded forward_position_controller
[ros2_control_node-1] [INFO] [1694491097.300579635] [controller_manager]: Configuring controller 'forward_position_controller'
[ros2_control_node-1] [INFO] [1694491097.303301231] [forward_position_controller]: configure successful
[spawner-3] [INFO] [1694491097.315730516] [spawner_joint_state_broadcaster]: Configured and activated joint_state_broadcaster
[ros2_control_node-1] [ERROR] [1694491097.324640301] [controller_manager]: Can't activate controller 'forward_position_controller': Command interface with 'fr_drive_joint,/position' does not exist
[spawner-4] [INFO] [1694491097.336035028] [spawner_forward_position_controller]: Configured and activated forward_position_controller
[INFO] [spawner-3]: process has finished cleanly [pid 32239]
[INFO] [spawner-4]: process has finished cleanly [pid 32241]
[ros2_control_node-1] [INFO] [1694491111.061080187] [fr_drive_joint]: Slave 0xC: Switched NMT state to START
[ros2_control_node-1] [INFO] [1694491111.362236565] [fr_drive_joint]: Slave 0xC: Switched NMT state to PREOP
[ros2_control_node-1] [INFO] [1694491116.761779116] [fr_drive_joint]: Slave 0xC: Switched NMT state to START

Does this behaviour still sort of align with your feedback on what is going on?

jclinton830 commented 9 months ago

@ipa-cmh any thoughts on the last comment above?

ipa-vsp commented 4 months ago

@jclinton830 Sorry for not following up earlier. Has the issue been resolved? I will close this ticket for now, but feel free to reopen it if you have any further comments.

jclinton830 commented 2 months ago

Hi @ipa-vsp, yes this is still an issue.