Show EOL distros: 

ros_canopen: can_msgs | canopen_402 | canopen_chain_node | canopen_master | canopen_motor_node | socketcan_bridge | socketcan_interface

Package Summary

This package extends the canopen_chain_node with specialized handling for canopen_402 devices. It facilitates interface abstraction with ros_control.

ros_canopen: can_msgs | canopen_402 | canopen_chain_node | canopen_master | canopen_motor_node | socketcan_bridge | socketcan_interface

Package Summary

This package extends the canopen_chain_node with specialized handling for canopen_402 devices. It facilitates interface abstraction with ros_control.

ros_canopen: can_msgs | canopen_402 | canopen_chain_node | canopen_master | canopen_motor_node | socketcan_bridge | socketcan_interface

Package Summary

canopen_chain_node specialization for handling of canopen_402 motor devices. It facilitates interface abstraction with ros_control.

ros_canopen: can_msgs | canopen_402 | canopen_chain_node | canopen_master | canopen_motor_node | socketcan_bridge | socketcan_interface

Package Summary

canopen_chain_node specialization for handling of canopen_402 motor devices. It facilitates interface abstraction with ros_control.

ros_canopen: can_msgs | canopen_402 | canopen_chain_node | canopen_master | canopen_motor_node | socketcan_bridge | socketcan_interface

Package Summary

canopen_chain_node specialization for handling of canopen_402 motor devices. It facilitates interface abstraction with ros_control.

Overview

The canopen_motor_node package provides a ros_control interface to [canopen_402]] compliant motors. It is based on canopen_chain_node and inherits all its interfaces, so this site just focuses on the additional interfaces.

Concepts

controller manager

The node includes a controller_manager instance that can be used to spawn controller_interface compliant controllers. Depending on the motor device different interfaces are support.

For each joint a hardware_interface::JointStateHandle is registered with the position, velocity and effort of the specific drive. The actual value is determined by the conversion functions.

In addition handles for the following command interfaces are available if the given modes are supported by the device:

  • hardware_interface::PositionJointInterface:

    • Profiled Position
    • Interpolated Position
    • Cyclic Synchronous Position
  • hardware_interface::VelocityJointInterface:

    • Velocity
    • Profiled Velocity
    • Cyclic Synchronous Velocity
  • hardware_interface::EffortJointInterface:

    • Profiled Torque
    • Cyclic Synchronous Torque

joint limits

The output from the controller is limited by joint_limits_interface and not passed directly to the motor. The limits can be read from URDF or the ParameterServer: https://github.com/ros-controls/ros_control/wiki/joint_limits_interface.

If certain limits are specified, the driver registers appropriate handles for soft and saturation limits.

mode switching

The driver does support mode switching at run-time and mixed modes for different joints. In order to determine the mode, a special parameter "required_drive_mode" must be added to each controller. It should contain the CANopen 402 mode id.

Since mode switching might be restricted to specific drive states by the manufacturer, the drive state for mode switching can be specified for each mode.

unit conversions

The driver features muparser based conversion functions.

In addition to the predefined functions and operators, the following functions are available:

  • rad2deg(radians): convert from radians to degrees
  • deg2rad(degrees): convert from degrees to radians
  • norm(value, min, max): normalize value to the range [min, max)
  • smooth(value, old_value, alpha): exponential smoothing, returns alpha*val + (1.0-alpha)*old_val

  • avg(val1,val2,...): average functions that stops on the first NaN value

Further two constants are defined for convenience: pi and nan.

The conversion functions from ROS the device units can read the commands from the respective pos,vel and eff variables.

The conversion functions from device to ROS supports an extended notion with obj prefixes: E.g. obj6064 will read the actual position and obj6091sub1 will read the gear ration nominator.

Please note that you can write to these variables, but you should avoid it, these writes are not passed to the device anyway and will overwritten in the next call!

You can define more variables by just using them, they will be initialized to NaN values.

Configuration

The basic configuration is described in canopen_chain_node#Configuration.

For the canopen_motor_node to work each node is given a joint parameter that defaults to the CANopen node name and is used as joint name in the ros_control interfaces.

For each motor node a motor_allocator can be specified which is used to load a motor plugin with pluginlib, it defaults to the canopen_402 implementation. All settings contained in the 'motor_layer' parameter will be passed to the motor layer instance.

In summary the following parameters are supported in defaults section and per node:

   1 defaults: # optional, all defaults can be overwritten per node
   2   # canopen_chain_node settings ..
   3   motor_allocator: canopen::Motor402::Allocator # select allocator for motor layer
   4   motor_layer: settings passed to motor layer (plugin-specific)
   5     switching_state: 5 # (Operation_Enable), state for mode switching
   6   pos_to_device: "rint(rad2deg(pos)*1000)" # rad -> mdeg
   7   pos_from_device: "deg2rad(obj6064)/1000" # actual position [mdeg] -> rad
   8   vel_to_device: "rint(rad2deg(vel)*1000)" # rad/s -> mdeg/s
   9   vel_from_device: "deg2rad(obj606C)/1000" # actual velocity [mdeg/s] -> rad/s
  10   eff_to_device: "rint(eff)" # just round to integer
  11   eff_from_device: "0" # unset

If omitted, the listed values are used.

The objects used in the conversion functions and the drive modes should be mapped to PDOs for best performance.

ROS API

The canopen_motor_node exposes the ROS interfaces of canopen_chain_node.

Please note that the init service will try to perform the drive homing if it's supported.

In addition the interfaces of controller_manager are available after initialization. However, the controller_manager is stopped when shutdown service ist called.

The joint_limits_interface will read its limits from the URDF and from the ParameterServer. The latter takes precedence but does not support soft limits.

The spawned controllers will provide additional interfaces.

C++ API

The current implementation does not expose a C++ API, but it is planned for the future: Issue #101

Wiki: canopen_motor_node (last edited 2018-07-24 13:36:50 by GvdHoorn)