ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

Canopen_master initializing failure with "std::bad_cast; Could not set transition"

asked 2022-09-13 10:26:35 -0500

mmmth gravatar image

updated 2022-09-19 02:22:34 -0500

Hi guys!

I'm new to ROS and I would like to use ros_canopen(0.8.5) package to control a motor (supporting Canopen) on a Rasberry Pi 4b (Ubuntu 18.04.5 + ros melodic). The current situation is that the canopen master cannot be initialized successfully with the error "std::bad cast; Could not set transition". I have looked up into many tutorials but it seems that I could not find a suitable solution for this error. I am stuck with this problem for a few days and I really need the help of the ROS community.

Here are the messages in the terminal after running the launch file.

process[controller_spawner-1]: started with pid [3810] process[canopen_motor_chain_node-2]: started with pid [3817] [INFO] [1663069518.006649346]: Using fixed control period: 0.010000000 process[robot_state_publisher-3]: started with pid [3840] process[joint_state_publisher-4]: started with pid [3861] process[init_driver-5]: started with pid [3874] [ INFO] [1663069522.544832547]: Initializing... [ INFO] [1663069522.545328712]: Current state: 1 device error: system:0 internal_error: 0 (OK) [ INFO] [1663069522.546353115]: Current state: 2 device error: system:0 internal_error: 0 (OK) [ WARN] [1663069524.567316957]: illegal transition 0 -> 2 [ INFO] [1663069524.567640758]: Current state: 2 device error: system:125 internal_error: 0 (OK) [ INFO] [1663069524.567782012]: Current state: 0 device error: system:125 internal_error: 0 (OK) [ INFO] [1663069524.567874619]: Current state: 0 device error: system:0 internal_error: 0 (OK) [ INFO] [1663069524.567978985]: Current state: 0 device error: system:0 internal_error: 0 (OK) [ERROR] [1663069524.568633236]: Initializing failed: /opt/ros/melodic/include/canopen_master/objdict.h(88): > Throw in function const T& canopen::HoldAny::get() const [with T = canopen::NodeIdOffset<short int="">] Dynamic exception type: >boost::exception_detail::clone_impl<boost::exception_detail::error_info_injector<std::bad_cast>> std::exception::what: std::bad_cast; Could not set transition

Obviously, there is a warning message "illegal transition 0->2" which I think it is thrown by canopen_402/src/motor.cpp in line 158 . I wonder if this has something to do with the error. Also, the code snippt of where it fails is given as follows.

template<typename T> const T & get() const{
    if(!type_guard.is_type<T>()){
        BOOST_THROW_EXCEPTION(std::bad_cast());
    }else if(empty){
        BOOST_THROW_EXCEPTION(std::length_error("buffer empty"));
    }
    return *(T*)&(buffer.front());
}

Here are the can frames collected from CAN bus during launching process.

can0 000 [2] 82 01

can0 701 [1] 00

can0 601 [8] 2B 17 10 00 00 00 00 00

can0 581 [8] 60 17 10 00 00 00 00 00

can0 000 [2] 01 01

can0 181 [2] 40 02

can0 601 [8] 2F 60 60 00 00 00 00 00

can0 581 [8] 60 60 60 00 00 00 00 00

can0 000 [2] 02 01

Here are the corresponding configuration files, including the configurations for motor controller, motor limitations and canopen. As can be seen in the canopen.yaml, there are no PDO remappings now. The .eds file has been checked by CANeds and is now error-free. The original one is here.

This question also follows on from a Github issue of ros_canopen.

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2022-09-16 08:55:04 -0500

miura gravatar image

It does not seem to work if multiple PDOs are assigned the same ID. In your case, it seems that 6040 and 6041 are assigned to multiple PDOs. Assigning it to one of the PDOs may improve things.

Also, since you set required_drive_mode: 1, I assume you want to run it as Profiled Position. In that case, you need to have 607A mapped to PRDO.

In addition, it is recommended to map 6061.

ref http://wiki.ros.org/canopen_402#Overview

edit flag offensive delete link more

Comments

1

Hi @miura! Thank you for your helpful answer. I have corrected those mistakes in my .eds file according to your suggestions and now the motor can be controlled through ros_canopen finally!

Actually, the multi PDOs assigned the same ID is one of the factors that cause the motor not to work properly but not the one leads to the error "std::bad_cast; Could not set transition". The most direct reason for this error is that there is an object in .eds file whose data type is inconsistent with the CiA 402, while I did not add it as a checking standard when using CANeds to check the .eds file, so this error was not spotted at the beginning. The so-called "error-free eds file" I mentioned in my question is not really error-free.

So, there is a tip about checking .eds files with CANeds, which is press "Ctrl+F2" and make ...(more)

mmmth gravatar image mmmth  ( 2022-09-18 11:44:10 -0500 )edit

Congrats to you and your family! Glad it's resolved!

miura gravatar image miura  ( 2022-09-19 06:17:56 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2022-09-13 10:22:42 -0500

Seen: 107 times

Last updated: Sep 19 '22