ros-industrial / ros_canopen

CANopen driver framework for ROS (http://wiki.ros.org/ros_canopen)
GNU Lesser General Public License v3.0
328 stars 267 forks source link

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

Closed augenstern-M closed 1 year ago

augenstern-M commented 1 year ago

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 Raspberry 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. However, I do found an issue #323 which is quite similar with this one . Unfortunately, no detailed solution is provided in that issue.

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.

class HoldAny{
    String buffer;
    TypeGuard type_guard;
    bool empty;
public:
    HoldAny() : empty(true) {}

    const TypeGuard& type() const{ return type_guard; }

    template<typename T> HoldAny(const T &t) : type_guard(TypeGuard::create<T>()), empty(false){
        buffer.resize(sizeof(T));
        *(T*)&(buffer.front()) = t;
    }
    HoldAny(const std::string &t): type_guard(TypeGuard::create<std::string>()), empty(false){
        if(!type_guard.is_type<std::string>()){
            BOOST_THROW_EXCEPTION(std::bad_cast());
        }
        buffer = t;
    }
    HoldAny(const TypeGuard &t): type_guard(t), empty(true){ }

    bool is_empty() const { return empty; }

    const String& data() const {
        if(empty){
            BOOST_THROW_EXCEPTION(std::length_error("buffer empty"));
        }
        return buffer;
    }

    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.

augenstern-M commented 1 year ago

@mathias-luedtke Hi! Do you have any clue about this error? Look forward to your reply! Thanks in advance.

mathias-luedtke commented 1 year ago

@augenstern-M: Have found the issue? It looks like the device does not behave like a regular CANopen 402 device, because it switches the motor on directly..

augenstern-M commented 1 year ago

@augenstern-M: Have found the issue? It looks like the device does not behave like a regular CANopen 402 device, because it switches the motor on directly..

Hi @mathias-luedtke ! Thank you for your answer. The problem has been solved and now I can control my motor through ros_canopen successfully. Here is the reason why this error occurred.