ros-industrial / ros2_canopen

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

Problem when starting the motor #146

Open MinElite opened 1 year ago

MinElite commented 1 year ago

Describe the bug Hello, I tried to use ros2_canopen to control a motor, following the instruction https://ros-industrial.github.io/ros2_canopen/manual/rolling/application/trinamic.html However, after launching the .launch file, the motor did not start successfully and the communication got stuck. The logs are as follows:

Logs

6.16log

launch

import os
import sys

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

def generate_launch_description():
    ld = LaunchDescription()
    slave_eds_path = os.path.join(
        get_package_share_directory("canopen_kinco"), "config", "kincoJD", "KINCO-JD.eds"
    )

    # slave_node_1 = IncludeLaunchDescription(
    #     PythonLaunchDescriptionSource(
    #         [
    #             os.path.join(get_package_share_directory("canopen_fake_slaves"), "launch"),
    #             "/cia402_slave.launch.py",
    #         ]
    #     ),
    #     launch_arguments={
    #         "node_id": "1",
    #         "node_name": "pd42_slave",
    #         "slave_config": slave_eds_path,
    #     }.items(),
    # )
    master_bin_path = os.path.join(
        get_package_share_directory("canopen_kinco"),
        "config",
        "kincoJD",
        "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_kinco"),
                "config",
                "kincoJD",
                "master.dcf",
            ),
            "master_bin": master_bin_path,
            "bus_config": os.path.join(
                get_package_share_directory("canopen_kinco"),
                "config",
                "kincoJD",
                "bus.yml",
            ),
            "can_interface_name": "can0",
        }.items(),
    )

    ld.add_action(device_container)
    #ld.add_action(slave_node_1)

    return ld
# bus:
options:
    dcf_path: "@BUS_CONFIG_PATH@"

master:
    node_id: 3
    driver: "ros2_canopen::MasterDriver"
    package: "canopen_master_driver"
    sync_period: 4000 # The SYNC interval in μs (default: 0).
    baudrate: 500000
    vendor_id: 0x00000300
    product_code: 0x4644
    # revision_number: 0
    # serial_number: 
    # heartbeat_multiplier

defaults:
    dcf: "KINCO-JD.eds"
    driver: "ros2_canopen::Cia402Driver"
    package: "canopen_402_driver"
    polling: false
    heartbeat_producer: 0 # Heartbeat every 1000 ms
    sdo: # SDO executed during config
        - {index: 0x6060, sub_index: 0, value: 6} # Set operating mode
        - {index: 0x60FF, sub_index: 0, value: 500000} # Set velocity
        #- {index: 0x6083, sub_index: 0, value: 1000000} # Set acceleration
        #- {index: 0x6083, sub_index: 0, value: 1000000} # Set deceleration
        #- {index: 0x6085, sub_index: 0, value: 1000000} # Set quickstop deceleration
        #- {index: 0x6098, sub_index: 0, value: 35} # Set default homing mode to 35
        #- {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

nodes:
    left_wheel:
        node_id: 1
yan@yan:~/ros/canopenoffical$ ros2 launch canopen_kinco direct_launch.launch.py 
[INFO] [launch]: All log files can be found below /home/yan/.ros/log/2023-06-16-17-07-35-217832-yan-249289
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [launch.user]: /home/yan/ros/canopenoffical/install/canopen_kinco/share/canopen_kinco/config/kincoJD/bus.yml
[INFO] [launch.user]: /home/yan/ros/canopenoffical/install/canopen_kinco/share/canopen_kinco/config/kincoJD/master.dcf
[INFO] [launch.user]: 
[INFO] [launch.user]: can0
[INFO] [device_container_node-1]: process started with pid [249301]
[device_container_node-1] [INFO] [1686906455.320493541] [device_container_node]: Starting Device Container with:
[device_container_node-1] [INFO] [1686906455.320588505] [device_container_node]:     master_config /home/yan/ros/canopenoffical/install/canopen_kinco/share/canopen_kinco/config/kincoJD/master.dcf
[device_container_node-1] [INFO] [1686906455.320599293] [device_container_node]:     bus_config /home/yan/ros/canopenoffical/install/canopen_kinco/share/canopen_kinco/config/kincoJD/bus.yml
[device_container_node-1] [INFO] [1686906455.320609120] [device_container_node]:     can_interface_name can0
[device_container_node-1] [INFO] [1686906455.321113584] [device_container_node]: Loading Master Configuration.
[device_container_node-1] [INFO] [1686906455.321514622] [device_container_node]: Load Library: /home/yan/ros/canopenoffical/install/canopen_master_driver/lib/libmaster_driver.so
[device_container_node-1] [INFO] [1686906455.324337172] [device_container_node]: Found class: rclcpp_components::NodeFactoryTemplate<ros2_canopen::MasterDriver>
[device_container_node-1] [INFO] [1686906455.324353042] [device_container_node]: Instantiate class: rclcpp_components::NodeFactoryTemplate<ros2_canopen::MasterDriver>
[device_container_node-1] [INFO] [1686906455.330078632] [master]: NodeCanopenBasicMaster
[device_container_node-1] [INFO] [1686906455.330151487] [device_container_node]: Load master component.
[device_container_node-1] [INFO] [1686906455.330186541] [device_container_node]: Added /master to executor
[device_container_node-1] NMT: entering reset application state
[device_container_node-1] NMT: entering reset communication state
[device_container_node-1] NMT: running as master
[device_container_node-1] NMT: entering pre-operational state
[device_container_node-1] NMT: entering operational state
[device_container_node-1] [INFO] [1686906455.341782918] [device_container_node]: Loading Driver Configuration.
[device_container_node-1] [INFO] [1686906455.341824725] [device_container_node]: Found device left_wheel with driver ros2_canopen::Cia402Driver
[device_container_node-1] [INFO] [1686906455.341940306] [device_container_node]: Load Library: /home/yan/ros/canopenoffical/install/canopen_402_driver/lib/libcia402_driver.so
[device_container_node-1] [INFO] [1686906455.345184565] [device_container_node]: Found class: rclcpp_components::NodeFactoryTemplate<ros2_canopen::Cia402Driver>
[device_container_node-1] [INFO] [1686906455.345196214] [device_container_node]: Instantiate class: rclcpp_components::NodeFactoryTemplate<ros2_canopen::Cia402Driver>
[device_container_node-1] [INFO] [1686906455.346566033] [device_container_node]: Load driver component.
[device_container_node-1] [INFO] [1686906455.346612747] [device_container_node]: Added /left_wheel to executor
[device_container_node-1] [INFO] [1686906455.357367091] [left_wheel]: 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] [1686906455.358637842] [left_wheel]: eds file /home/yan/ros/canopenoffical/install/canopen_kinco/share/canopen_kinco/config/kincoJD/KINCO-JD.eds
[device_container_node-1] [INFO] [1686906455.358658021] [left_wheel]: bin file /home/yan/ros/canopenoffical/install/canopen_kinco/share/canopen_kinco/config/kincoJD/left_wheel.bin
[device_container_node-1] 6099sub3: warning: 8-bit unsigned integer overflow: Numerical result out of range
[device_container_node-1] 6099sub4: warning: 16-bit signed integer overflow: Numerical result out of range
[device_container_node-1] 6099sub5: warning: 8-bit unsigned integer overflow: Numerical result out of range
[device_container_node-1] 6099sub6: warning: 8-bit unsigned integer overflow: Numerical result out of range
[device_container_node-1] 2010sub0: warning: DefaultValue overflow
[device_container_node-1] 2010sub0: warning: ParameterValue overflow
[device_container_node-1] Found rpdo mapped object: index=607a subindex=0
[device_container_node-1] Found rpdo mapped object: index=6060 subindex=0
[device_container_node-1] Found rpdo mapped object: index=6040 subindex=0
[device_container_node-1] Found rpdo mapped object: index=6081 subindex=0
[device_container_node-1] Found rpdo mapped object: index=60ff subindex=0
[device_container_node-1] Found tpdo mapped object: index=6041 subindex=0
[device_container_node-1] Found tpdo mapped object: index=6063 subindex=0
[device_container_node-1] Found tpdo mapped object: index=6061 subindex=0
[device_container_node-1] [WARN] [1686906455.363549075] [left_wheel]: Wait for device to boot.
[device_container_node-1] warning: error writing CAN frame: Operation canceled
[device_container_node-1] CAN frame successfully written after 125 write errors
[device_container_node-1] [ERROR] [1686906461.629942208] [left_wheel]: Boot Issue: Value of object 1018:02 from CANopen device is different to value in object 1F86 (Product code).
[device_container_node-1] [INFO] [1686906461.630067837] [left_wheel]: Driver booted and ready.
[device_container_node-1] [INFO] [1686906461.630756813] [left_wheel]: Starting with event mode.
[device_container_node-1] [INFO] [1686906461.632791441] [canopen_402_driver]: Fault reset
[device_container_node-1] sync_sdo_read_typed: id=1 index=0x6064 subindex=0 timed out.

start init

yan@yan:~/ros/canopenoffical$ ros2 service call /left_wheel/init std_srvs/srv/Trigger 
requester: making request: std_srvs.srv.Trigger_Request()

candump:

  can0  703   [1]  00
  can0  000   [2]  82 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  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  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  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  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  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  080   [0] 
  can0  702   [1]  00
  can0  702   [1]  00
  can0  080   [0] 
  can0  701   [1]  00
  can0  601   [8]  40 00 10 00 00 00 00 00
  can0  581   [8]  43 00 10 00 92 01 02 00
  can0  601   [8]  40 18 10 01 00 00 00 00
  can0  080   [0] 
  can0  581   [8]  43 18 10 01 00 03 00 00
  can0  601   [8]  40 18 10 02 00 00 00 00
  can0  581   [8]  43 18 10 02 44 46 00 00
  can0  080   [0] 

Setup:

It's difficult for me to locate the problem. Any hint?

Thanks a lot!

bjsowa commented 1 year ago

I believe I am facing i similar issue. My theory is that in the event mode, SDO requests (using universal_set_value and universal_get_value methods) called from poll_timer_callback do not work. In my case the first request results in a timeout, the second one hangs on this line: https://github.com/ros-industrial/ros2_canopen/blob/master/canopen_base_driver/include/canopen_base_driver/lely_driver_bridge.hpp#L443 Waiting for sdo_cond condition variable to be notified.

With #147 and polling mode enabled, this issue does not happen.

MinElite commented 1 year ago

Thanks!

Well, after setting polling mode to true. I got a new issue here.

yan@yan:~/ros/canopenoffical$ ros2 launch canopen_kinco direct_launch.launch.py [INFO] [launch]: All log files can be found below /home/yan/.ros/log/2023-06-19-17-49-58-754836-yan-455625 [INFO] [launch]: Default logging verbosity is set to INFO

[INFO] [launch.user]:

[INFO] [device_container_node-1]: process started with pid [455637] [device_container_node-1] [INFO] [1687168198.905473441] [device_container_node]: Starting Device Container with: [device_container_node-1] [INFO] [1687168198.905544307] [device_container_node]: master_config /home/yan/ros/canopenoffical/install/canopen_kinco/share/canopen_kinco/config/kincoJD/master.dcf [device_container_node-1] [INFO] [1687168198.905550846] [device_container_node]: bus_config /home/yan/ros/canopenoffical/install/canopen_kinco/share/canopen_kinco/config/kincoJD/bus.yml [device_container_node-1] [INFO] [1687168198.905557669] [device_container_node]: can_interface_name can0 [device_container_node-1] [INFO] [1687168198.906182040] [device_container_node]: Loading Master Configuration. [device_container_node-1] [INFO] [1687168198.906460375] [device_container_node]: Load Library: /home/yan/ros/canopenoffical/install/canopen_master_driver/lib/libmaster_driver.so [device_container_node-1] [INFO] [1687168198.908296176] [device_container_node]: Found class: rclcpp_components::NodeFactoryTemplate [device_container_node-1] [INFO] [1687168198.908313180] [device_container_node]: Instantiate class: rclcpp_components::NodeFactoryTemplate

[device_container_node-1] [INFO] [1687168198.916307494] [device_container_node]: Load master component. [device_container_node-1] [INFO] [1687168198.916364424] [device_container_node]: Added /master to executor [device_container_node-1] NMT: entering reset application state [device_container_node-1] NMT: entering reset communication state [device_container_node-1] NMT: running as master [device_container_node-1] NMT: entering pre-operational state [device_container_node-1] NMT: entering operational state [device_container_node-1] [INFO] [1687168198.933440004] [device_container_node]: Loading Driver Configuration. [device_container_node-1] [INFO] [1687168198.933526305] [device_container_node]: Found device left_wheel with driver ros2_canopen::Cia402Driver [device_container_node-1] [INFO] [1687168198.933727937] [device_container_node]: Load Library: /home/yan/ros/canopenoffical/install/canopen_402_driver/lib/libcia402_driver.so [device_container_node-1] [INFO] [1687168198.937081524] [device_container_node]: Found class: rclcpp_components::NodeFactoryTemplate [device_container_node-1] [INFO] [1687168198.937095521] [device_container_node]: Instantiate class: rclcpp_components::NodeFactoryTemplate [device_container_node-1] [INFO] [1687168198.938584978] [device_container_node]: Load driver component. [device_container_node-1] [INFO] [1687168198.938640334] [device_container_node]: Added /left_wheel to executor [device_container_node-1] [ERROR] [1687168198.952255032] [left_wheel]: Could not read period from config, setting to 10ms [device_container_node-1] [INFO] [1687168198.952381022] [left_wheel]: scale_pos_todev 1000.000000 [device_container_node-1] scale_pos_fromdev 0.001000 [device_container_node-1] scale_vel_todev 1000.000000 [device_container_node-1] scale_vel_fromdev 0.001000 [device_container_node-1] [device_container_node-1] [INFO] [1687168198.953110439] [left_wheel]: eds file /home/yan/ros/canopenoffical/install/canopen_kinco/share/canopen_kinco/config/kincoJD/KINCO-JD.eds [device_container_node-1] [INFO] [1687168198.953121344] [left_wheel]: bin file /home/yan/ros/canopenoffical/install/canopen_kinco/share/canopen_kinco/config/kincoJD/left_wheel.bin [device_container_node-1] 6099sub3: warning: 8-bit unsigned integer overflow: Numerical result out of range [device_container_node-1] 6099sub4: warning: 16-bit signed integer overflow: Numerical result out of range [device_container_node-1] 6099sub5: warning: 8-bit unsigned integer overflow: Numerical result out of range [device_container_node-1] 6099sub6: warning: 8-bit unsigned integer overflow: Numerical result out of range [device_container_node-1] 2010sub0: warning: DefaultValue overflow [device_container_node-1] 2010sub0: warning: ParameterValue overflow [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=6040 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 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=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] [WARN] [1687168198.956558396] [left_wheel]: Wait for device to boot. [device_container_node-1] warning: error writing CAN frame: Operation canceled [device_container_node-1] CAN frame successfully written after 125 write errors [device_container_node-1] [ERROR] [1687168220.236889549] [left_wheel]: Boot Issue: Value of object 1018:02 from CANopen device is different to value in object 1F86 (Product code). [device_container_node-1] [INFO] [1687168220.237024033] [left_wheel]: Driver booted and ready. [device_container_node-1] [INFO] [1687168220.237855459] [left_wheel]: Starting with polling mode. [device_container_node-1] [INFO] [1687168220.249467846] [canopen_402_driver]: Fault reset [device_container_node-1] async_sdo_read: id=1 index=0x6502 subindex=0 object does not exist [device_container_node-1] [ERROR] [1687168230.760567376] [left_wheel]: 01:6502:00: Object does not exist in the object dictionary (06020000): Object does not exist in the object dictionary [ERROR] [device_container_node-1]: process has died [pid 455637, exit code -11, cmd '/home/yan/ros/canopenoffical/install/canopen_core/lib/canopen_core/device_container_node --ros-args -r node:=device_container_node -r ns:=/ --params-file /tmp/launch_params__20gobrh --params-file /tmp/launch_params_xj0pmj57 --params-file /tmp/launch_params_80e3626b --params-file /tmp/launch_params_arlni5xg'].

It seems like an object which does not exist in the .eds file was called. Is it possible to locate which function did ask for this object and then deactivate it?

hellantos commented 1 year ago

@MinElite Your problem is this:

 Boot Issue: Value of object 1018:02 from CANopen device is different to value in object 1F86 (Product code).

The product code of the device connected to the bus is not the same as indicated in the eds file that should describe the device. The device connected returns

Basically your device returns: 43 18 10 02 44 46 00 00 The value in the eds file under 0x1018sub2 should be 0x4644 --> 17988 (I believe from you output).

Also if your device is a cia402 device, 0x6502 has to exist, as it indicates which operation modes your device supports.

My suggestion is to first try the proxy driver on the device. Once proxy driver is working go with the cia402_driver.

If you pull from master you'll now have #147 included.

MinElite commented 1 year ago

Hi,

many thanks for the reply!

The product code of the device connected to the bus is not the same as indicated in the eds file that should describe the device. The device connected returns

Basically your device returns: 43 18 10 02 44 46 00 00 The value in the eds file under 0x1018sub2 should be 0x4644 --> 17988 (I believe from you output).

I did correct the product code in the .eds file. But the same error was still there. Moreover, as I tried the example in https://github.com/ipa-cmh/trinamic_pd42_can with mock_launch and vcan0, a similar error occurred, which shown that the revision number did not match. Anyway, despite this error the program continued to run.

My suggestion is to first try the proxy driver on the device. Once proxy driver is working go with the cia402_driver.

The proxy driver works. Cia402_driver still has the same error (0x6502 not found). I would like to know if it is possible to use the proxy driver instead of cia402_driver to create a robot system with ros2_control?

If you pull from master you'll now have #147 included.

I had some building issues with the master branch ( my system: Ubuntu 22.04, ROS2 Humble), see below:

--- stderr: canopen_core                                
In file included from /home/elite/canopen_ws/src/ros2_canopen/canopen_core/src/device_container.cpp:16:
/home/elite/canopen_ws/src/ros2_canopen/canopen_core/include/canopen_core/device_container.hpp: In constructor ‘ros2_canopen::DeviceContainer::DeviceContainer(std::weak_ptr<rclcpp::Executor>, std::string, const rclcpp::NodeOptions&)’:
/home/elite/canopen_ws/src/ros2_canopen/canopen_core/include/canopen_core/device_container.hpp:67:81: error: no matching function for call to ‘ros2_canopen::DeviceContainer::create_service<canopen_interfaces::srv::CONode>(const char [14], std::_Bind_helper<false, void (ros2_canopen::DeviceContainer::*)(std::shared_ptr<canopen_interfaces::srv::CONode_Request_<std::allocator<void> > >, std::shared_ptr<canopen_interfaces::srv::CONode_Response_<std::allocator<void> > >), ros2_canopen::DeviceContainer*, const std::_Placeholder<1>&, const std::_Placeholder<2>&>::type, rclcpp::QoS, rclcpp::CallbackGroup::SharedPtr&)’
   67 | river_service_ = this->create_service<canopen_interfaces::srv::CONode>(
      |                  ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~^

   68 | nit_driver",
      | ~~~~~~~~~~~~                                                           

   69 | :bind(
      | ~~~~~~                                                                 

   70 | eviceContainer::on_init_driver, this, std::placeholders::_1, std::placeholders::_2),
      | ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~

   71 | pp::QoS(10), client_cbg_);
      | ~~~~~~~~~~~~~~~~~~~~~~~~~                                              

In file included from /opt/ros/humble/include/rclcpp/rclcpp/executors/single_threaded_executor.hpp:28,
                 from /opt/ros/humble/include/rclcpp/rclcpp/executors.hpp:22,
                 from /home/elite/canopen_ws/src/ros2_canopen/canopen_core/include/canopen_core/device_container.hpp:21,
                 from /home/elite/canopen_ws/src/ros2_canopen/canopen_core/src/device_container.cpp:16:
/opt/ros/humble/include/rclcpp/rclcpp/node.hpp:267:3: note: candidate: ‘template<class ServiceT, class CallbackT> typename rclcpp::Service<ServiceT>::SharedPtr rclcpp::Node::create_service(const string&, CallbackT&&, const rmw_qos_profile_t&, rclcpp::CallbackGroup::SharedPtr)’
  267 |   create_service(
      |   ^~~~~~~~~~~~~~
/opt/ros/humble/include/rclcpp/rclcpp/node.hpp:267:3: note:   template argument deduction/substitution failed:
In file included from /home/elite/canopen_ws/src/ros2_canopen/canopen_core/src/device_container.cpp:16:
/home/elite/canopen_ws/src/ros2_canopen/canopen_core/include/canopen_core/device_container.hpp:71:15: note:   cannot convert ‘rclcpp::QoS(10)’ (type ‘rclcpp::QoS’) to type ‘const rmw_qos_profile_t&’ {aka ‘const rmw_qos_profile_s&’}
   71 |       rclcpp::QoS(10), client_cbg_);
      |               ^~~~~~~
gmake[2]: *** [CMakeFiles/device_container.dir/build.make:76: CMakeFiles/device_container.dir/src/device_container.cpp.o] Error 1
gmake[1]: *** [CMakeFiles/Makefile2:264: CMakeFiles/device_container.dir/all] Error 2
gmake[1]: *** Waiting for unfinished jobs....
gmake: *** [Makefile:146: all] Error 2
---
Failed   <<< canopen_core [19.1s, exited with code 2]

Would the master branch only work for rolling?

Cheers,

ipa-vsp commented 1 year ago

Hi @MinElite,

Yes, the master branch is for rolling. You can check out the humble branch to fix the build issues.

hellantos commented 1 year ago

@MinElite checkout canopen_system as interface. You will not have a robot controller though. There we only have single axis controllers.

If you want to avoid the check for revision code, set it to zero in the bus.yml.

hellantos commented 1 year ago

Just checked the kinco-jd manual. Their implementation of cia402 seems a bit sketchy. I could be that more than object 0x6502 is missing. We require 0x6502 to figure out which operation modes the drive supports. I can check how much work it is to set a fixed value for 0x6502.