ros-industrial / ros2_canopen

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

Mirroring a RPDO message via sending a TPDO Message with the same content #157

Open NB-ENG23 opened 1 year ago

NB-ENG23 commented 1 year ago

### _Launch file : cia402slave.launch.py import os import sys

sys.path.insert(0, os.path.join(os.path.dirname(file), "..")) # noqa sys.path.insert(0, os.path.join(os.path.dirname(file), "..", "..", "launch")) # noqa

import launch import launch.actions import launch.events from launch.substitutions import LaunchConfiguration, PythonExpression, TextSubstitution from launch.actions import DeclareLaunchArgument

import launch_ros import launch_ros.events import launch_ros.events.lifecycle

import lifecycle_msgs.msg

def generate_launch_description(): path_to_test = os.path.dirname(file)

node_id_arg = DeclareLaunchArgument(
    "node_id",
    default_value=TextSubstitution(text="2"),
    description="CANopen node id the mock slave shall have.",
)

slave_config_arg = DeclareLaunchArgument(
    "slave_config",
    default_value=TextSubstitution(
        text=os.path.join(path_to_test, "..", "config", "cia402_slave.eds")
    ),
    description="Path to eds file to be used for the slave.",
)

can_interface_name_arg = DeclareLaunchArgument(
    "can_interface_name",
    default_value=TextSubstitution(text="vcan0"),
    description="CAN interface to be used by mock slave.",
)

node_name_arg = DeclareLaunchArgument(
    "node_name",
    default_value=TextSubstitution(text="basic_slave_node"),
    description="Name of the node.",
)

slave_node = launch_ros.actions.LifecycleNode(
    name=LaunchConfiguration("node_name"),
    namespace="",
    package="canopen_fake_slaves",
    output="screen",
    executable="cia402_slave_node",
    parameters=[
        {
            "slave_config": LaunchConfiguration("slave_config"),
            "node_id": LaunchConfiguration("node_id"),
            "can_interface_name": LaunchConfiguration("can_interface_name"),
        }
    ],
)
slave_inactive_state_handler = launch.actions.RegisterEventHandler(
    launch_ros.event_handlers.OnStateTransition(
        target_lifecycle_node=slave_node,
        goal_state="inactive",
        handle_once=True,
        entities=[
            launch.actions.LogInfo(
                msg="node 'basic_slave_node' reached the 'inactive' state, 'activating'."
            ),
            launch.actions.EmitEvent(
                event=launch_ros.events.lifecycle.ChangeState(
                    lifecycle_node_matcher=launch.events.matches_action(slave_node),
                    transition_id=lifecycle_msgs.msg.Transition.TRANSITION_ACTIVATE,
                )
            ),
        ],
    ),
)
slave_configure = launch.actions.EmitEvent(
    event=launch_ros.events.lifecycle.ChangeState(
        lifecycle_node_matcher=launch.events.matches_action(slave_node),
        transition_id=lifecycle_msgs.msg.Transition.TRANSITION_CONFIGURE,
    )
)
ld = launch.LaunchDescription()
ld.add_action(node_id_arg)
ld.add_action(slave_config_arg)
ld.add_action(can_interface_name_arg)
ld.add_action(node_name_arg)
ld.add_action(slave_inactive_state_handler)
ld.add_action(slave_node)
ld.add_action(slave_configure)
return ld

In the Terminal :

INFO] [launch]: All log files can be found below /home/u20/.ros/log/2023-06-22-14-20-49-950608-u20-VirtualBox-2503
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [cia402_slave_node-1]: process started with pid [2514]
[cia402_slave_node-1] [INFO] [1687436450.616698168] [basic_slave_node]: Reaching inactive state.
[INFO] [launch.user]: node 'basic_slave_node' reached the 'inactive' state, 'activating'.
[cia402_slave_node-1] [INFO] [1687436450.622563621] [basic_slave_node]: Reaching active state.
[cia402_slave_node-1] NMT: entering reset application state
[cia402_slave_node-1] NMT: entering reset communication state
[cia402_slave_node-1] NMT: running as slave
[cia402_slave_node-1] NMT: entering pre-operational state
[cia402_slave_node-1] NMT: entering operational state
[cia402_slave_node-1] [INFO] [1687436450.633235780] [basic_slave_node]: Created cia402 slave for node_id 2.
[cia402_slave_node-1] [INFO] [1687436567.052513586] [cia402_slave]: Switch_On_Disabled
### [cia402_slave_node-1] [INFO] [1687436567.052832489] [cia402_slave]: Switched to mode 4.

**Command Candump vcan0 :** 

  vcan0  302   [3]  00 00 04

And i want to get a result message 

 vcan0  282   [3]  00 00 04   ( TPDO2 )

So , I was wondering is there  already any defined function that gives this result or is there any guidlines .            
NB-ENG23 commented 1 year ago

Command Candump vcan0 :

vcan0 302 [3] 00 00 04

And i want to get a result message

vcan0 282 [3] 00 00 04 ( TPDO2 )

So , I was wondering is there already any defined function that gives this result or is there any guidlines .

hellantos commented 1 year ago

You mean in the fake slave mirroring the input? There is a stupid implementation of this in basic slave which receives something on 0x4000 and returns it on 0x4001 via pdo.

Check the code it is pretty simple. You can extend it! https://github.com/ros-industrial/ros2_canopen/blob/master/canopen_fake_slaves/include/canopen_fake_slaves/basic_slave.hpp

NB-ENG23 commented 1 year ago

the basic fake slave is working correctly . but I didn't understand why the same function OnWrite () in cia402_slave.hpp doesn't give the same results : For the object Operation Mode with (indx = 6060 , subidx = 0 ) sending this message (RPDO 2) : cansend vcan0 302#000003 i don't receive a TPDO2 or any other message .

hellantos commented 1 year ago

Well that is the way pdo's work, they are one way. In our setup, slave's tpdos are usually triggered by a sync signal. If you did not map object 0x6060sub0 as rpdo and tpdo, there will not be a response.

NB-ENG23 commented 1 year ago

CIA402 EDS File : [1601sub1]

ParameterName=Mapping Entry 1

ObjectType=0x07

DataType=0x0007

AccessType=rw

DefaultValue=0x60600008

PDOMapping=0

[6060]

ParameterName=Modes of Operation 1

DataType=0x0002

AccessType=rww

DefaultValue=0x00

PDOMapping=1

The Function responsible for this result : if (idx == 0x6060 && subidx==0x00) { int8_t mode = (this)[0x6060][0]; switch (mode) { case No_Mode: case Profiled_Position: case Velocity: case Profiled_Velocity: case Profiled_Torque: case Reserved: case Homing: case Interpolated_Position: case Cyclic_Synchronous_Position: case Cyclic_Synchronous_Velocity: case Cyclic_Synchronous_Torque: operation_mode.store(mode); break; default: std::cout << "Error: Master tried to set unknown operation mode." << std::endl; } RCLCPP_INFO(rclcpp::get_logger("cia402_slave"), "Switched to mode %hhi.", mode); (this)[0x6061][0] = (int8_t)(mode); this->TpdoEvent(1); } }

sending an RPDO2 : 302#01 => the value of the index 6060 changed but don't get a TPDO ( 282#01 )

So I wondering what could be the thing that i am missing ?

hellantos commented 1 year ago

0x6060 is only mapped as RPDO, not TPDO at least from what I can see here. That is why it is not returned.

NB-ENG23 commented 1 year ago

Yes , the value will be stored in the index 0x6061 which is mapped a TPDO : In the function if (idx == 0x6060 && subidx==0x00) { int8_t mode = (this)[0x6060][0]; switch (mode) { case No_Mode: case Profiled_Position: case Velocity: case Profiled_Velocity: case Profiled_Torque: case Reserved: case Homing: case Interpolated_Position: case Cyclic_Synchronous_Position: case Cyclic_Synchronous_Velocity: case Cyclic_Synchronous_Torque: operation_mode.store(mode); break; default: std::cout << "Error: Master tried to set unknown operation mode." << std::endl; } RCLCPP_INFO(rclcpp::get_logger("cia402_slave"), "Switched to mode %hhi.", mode); (this)[0x6061][0] = (int8_t)(mode); this->TpdoEvent(1); } }

### in the EDS file [1A01sub2] ParameterName=Mapping Entry 2 ObjectType=0x07 DataType=0x0007 AccessType=rw DefaultValue=0x60610008 PDOMapping=0

[6061] ParameterName=Modes of Operation Display 1 ObjectType=0x07 DataType=0x0002 AccessType=ro PDOMapping=1

but never get the result .

NB-ENG23 commented 1 year ago

@ipa-cmh any hints or links to figure out why it doesn't work ? , i would be very grateful

hellantos commented 11 months ago

@NB-ENG23 Sorry I was on leave for a while. We'd probably have to have a small meeting to discuss this. I still do ot understand 100% what the problem is.