-
Notifications
You must be signed in to change notification settings - Fork 313
Description
Affected ROS2 Driver version(s)
humble
Used ROS distribution.
Humble
Which combination of platform is the ROS driver running on.
Ubuntu Linux with standard kernel
How is the UR ROS2 Driver installed.
Build both the ROS driver and UR Client Library from source
Which robot platform is the driver connected to.
Real robot
Robot SW / URSim version(s)
Polyscope X - 10.11.0
How is the ROS driver used.
Through the robot teach pendant using External Control URCap
Issue details
Summary
When running ROS2 control controller manager node that starts the UR hardware interface if I just configure it but don't activate it I get this error [UR_Client_Library:]: The type should be 1, 2 or 3. The type is 0.
Issue details
When running the controller manager it is possible to leave the hardware interface unconfigured or inactive and later activate. If I activate immediately after configuring, everything works fine. But if I leave the hw interface inactive or configure it after (without activating) I get this error:
[UR_Client_Library:]: The type should be 1, 2 or 3. The type is 0The error is caused by this code being in the on_activate function:
hardware_interface::CallbackReturn
URPositionHardwareInterface::on_activate(const rclcpp_lifecycle::State& previous_state)
{
RCLCPP_INFO(rclcpp::get_logger("URPositionHardwareInterface"), "Activating HW interface");
for (size_t i = 0; i < 6; i++) {
force_mode_task_frame_[i] = NO_NEW_CMD_;
force_mode_selection_vector_[i] = static_cast<uint32_t>(NO_NEW_CMD_);
force_mode_wrench_[i] = NO_NEW_CMD_;
force_mode_limits_[i] = NO_NEW_CMD_;
}
force_mode_type_ = static_cast<unsigned int>(NO_NEW_CMD_);
return hardware_interface::CallbackReturn::SUCCESS;
}Before setting the force_mode_type_ to NO_NEW_CMD_ whenever we try to use it in a separate thread (which the hw interface is probably doing` it throws the error.
Steps to Reproduce
- Start the
ur_control.launchon a real robot. - Unconfigure the hardware interface
- Configure the hardware interface
Expected Behavior
No errors when configuring the hardware interface. It is sometimes worth leaving the hw interface inactive to let other hardware interfaces configure before activating everything.
Actual Behavior
An error is thrown because the value is not set before activation.
Workaround Suggestion
Move the force_mode related code to the end of the on_configure function.
Relevant log output
[ur_ros2_control_node-6] [INFO] [1765817022.208058440] [resource_manager]: 'configure' hardware 'manipulator'
[ur_ros2_control_node-6] [INFO] [1765817022.208103464] [URPositionHardwareInterface]: Starting ...please wait...
[ur_ros2_control_node-6] [INFO] [1765817022.208141687] [URPositionHardwareInterface]: Initializing driver...
[ur_ros2_control_node-6] [INFO] [1765817022.208999058] [UR_Client_Library:]: SCHED_FIFO OK, priority 99
[ur_ros2_control_node-6] [INFO] [1765817022.210552823] [UR_Client_Library:]: Negotiated RTDE protocol version to 2.
[ur_ros2_control_node-6] [INFO] [1765817022.210954725] [UR_Client_Library:]: Setting up RTDE communication with frequency 500.000000
[ur_ros2_control_node-6] [INFO] [1765817023.260389325] [UR_Client_Library:]: Starting primary client pipeline
[ur_ros2_control_node-6] [INFO] [1765817023.323961477] [URPositionHardwareInterface]: Calibration checksum: 'calib_221927923814618764'.
[ur_ros2_control_node-6] [INFO] [1765817023.324003272] [URPositionHardwareInterface]: Calibration checked successfully.
[ur_ros2_control_node-6] [INFO] [1765817023.324068477] [URPositionHardwareInterface]: System successfully started!
[ur_ros2_control_node-6] [INFO] [1765817023.324088784] [resource_manager]: Successful 'configure' of hardware 'manipulator'
[ur_ros2_control_node-6] [INFO] [1765817023.324408191] [UR_Client_Library:]: SCHED_FIFO OK, priority 99
[ros2-7] Successfully set manipulator to state lifecycle_msgs.msg.State(id=2, label='inactive')
[ur_ros2_control_node-6] [INFO] [1765817023.350488441] [UR_Client_Library:]: Robot connected to reverse interface. Ready to receive control commands.
[ur_ros2_control_node-6] [ERROR] [1765817023.352099246] [UR_Client_Library:]: The type should be 1, 2 or 3. The type is 0
[ur_ros2_control_node-6] terminate called after throwing an instance of 'urcl::InvalidRange'
[ur_ros2_control_node-6] what(): The type should be 1, 2 or 3. The type is 0
[ur_ros2_control_node-6] Stack trace (most recent call last) in thread 419077:
[ur_ros2_control_node-6] #17 Object "", at 0xffffffffffffffff, in
[ur_ros2_control_node-6] #16 Object "/usr/lib/x86_64-linux-gnu/libc.so.6", at 0x79a97354e8bf, in
[ur_ros2_control_node-6] #15 Object "/usr/lib/x86_64-linux-gnu/libc.so.6", at 0x79a9734bcac2, in
[ur_ros2_control_node-6] #14 Object "/usr/lib/x86_64-linux-gnu/libstdc++.so.6.0.30", at 0x79a97374f252, in
[ur_ros2_control_node-6] #13 Object "/workspaces/isaac_ros-dev/ros_ws/install/ur_robot_driver/lib/ur_robot_driver/ur_ros2_control_node", at 0x5c29fa6c862a, in main::{lambda()#1}::operator()() const
[ur_ros2_control_node-6] #12 Object "/workspaces/isaac_ros-dev/ros_ws/install/controller_manager/lib/libcontroller_manager.so", at 0x79a973bb6084, in controller_manager::ControllerManager::write(rclcpp::Time const&, rclcpp::Duration const&)
[ur_ros2_control_node-6] #11 Object "/workspaces/isaac_ros-dev/ros_ws/install/hardware_interface/lib/libhardware_interface.so", at 0x79a973308b7c, in hardware_interface::ResourceManager::write(rclcpp::Time const&, rclcpp::Duration const&)
[ur_ros2_control_node-6] #10 Object "/workspaces/isaac_ros-dev/ros_ws/install/hardware_interface/lib/libhardware_interface.so", at 0x79a9733403af, in hardware_interface::System::write(rclcpp::Time const&, rclcpp::Duration const&)
[ur_ros2_control_node-6] #9 Object "/workspaces/isaac_ros-dev/ros_ws/install/ur_robot_driver/lib/libur_robot_driver_plugin.so", at 0x79a97038c71e, in ur_robot_driver::URPositionHardwareInterface::write(rclcpp::Time const&, rclcpp::Duration const&)
[ur_ros2_control_node-6] #8 Object "/workspaces/isaac_ros-dev/ros_ws/install/ur_robot_driver/lib/libur_robot_driver_plugin.so", at 0x79a9703855cc, in ur_robot_driver::URPositionHardwareInterface::start_force_mode()
[ur_ros2_control_node-6] #7 Object "/workspaces/isaac_ros-dev/ros_ws/install/ur_client_library/lib/liburcl.so", at 0x79a9704f8393, in urcl::UrDriver::startForceMode(std::array<double, 6ul> const&, std::array<unsigned int, 6ul> const&, std::array<double, 6ul> const&, unsigned int, std::array<double, 6ul> const&, double, double) [clone .cold]
[ur_ros2_control_node-6] #6 Object "/usr/lib/x86_64-linux-gnu/libstdc++.so.6.0.30", at 0x79a9737214d7, in __cxa_throw
[ur_ros2_control_node-6] #5 Object "/usr/lib/x86_64-linux-gnu/libstdc++.so.6.0.30", at 0x79a973721276, in std::terminate()
[ur_ros2_control_node-6] #4 Object "/usr/lib/x86_64-linux-gnu/libstdc++.so.6.0.30", at 0x79a97372120b, in
[ur_ros2_control_node-6] #3 Object "/usr/lib/x86_64-linux-gnu/libstdc++.so.6.0.30", at 0x79a973715b9d, in
[ur_ros2_control_node-6] #2 Object "/usr/lib/x86_64-linux-gnu/libc.so.6", at 0x79a9734507f2, in abort
[ur_ros2_control_node-6] #1 Object "/usr/lib/x86_64-linux-gnu/libc.so.6", at 0x79a97346a475, in raise
[ur_ros2_control_node-6] #0 Object "/usr/lib/x86_64-linux-gnu/libc.so.6", at 0x79a9734be9fc, in pthread_kill
[ur_ros2_control_node-6] Aborted (Signal sent by tkill() 419033 1000)
[ERROR] [ur_ros2_control_node-6]: process has diedAccept Public visibility
- I agree to make this context public