CAN Driver

This package provides an interface between high level ROS packages and handler of CAN Bus. It uses the mcp_can_rpi for CAN bus communication.
It is used by only Ned and the Niryo One.

CAN Driver Node (For only the development and debugging propose)

The ROS Node is made to:
  • Initialize CAN Interface.

CAN Interface Core

It is instantiated in Niryo Robot Hardware Interface package.

It has been conceived to:
  • Initialize the CAN Interface and physical bus with the configurations.
  • Add, remove and monitor devices on bus.
  • Start control loop to get and send data from/to motors.
  • Start ROS stuffs like services, topics if they exist.

It belongs to the ROS namespace: /can_driver/.

Parameters

Note

These configuration parameters are set to work with Niryo’s robot. Do not edit them.

CAN Driver’s Parameters
Name Description
can_hardware_control_loop_frequency
Control loop frequency.
Default: ‘1500.0’
can_hw_write_frequency
Write frequency.
Default: ‘200.0’
can_hw_read_frequency
Read frequency.
Default: ‘50.0’
bus_params/spi_channel
spi channel.
Default: ‘0’
bus_params/spi_baudrate
Baudrate.
Default: ‘1000000’
bus_params/gpio_can_interrupt
GPIO Interrupt.
Default: ‘25’

Services, Topics and Messages

StepperCmd (Service)

uint8 cmd_type
uint8 CMD_TYPE_SYNCHRONIZE=5
uint8 CMD_TYPE_RELATIVE_MOVE=6
uint8 CMD_TYPE_MAX_EFFORT=7
uint8 CMD_TYPE_MICRO_STEPS=8
uint8 CMD_TYPE_POSITION_OFFSET=9
uint8 CMD_TYPE_CALIBRATION=10

uint8[] motors_id
int32[] params
---
bool result

StepperMotorHardwareStatus (Message)

niryo_robot_msgs/MotorHeader motor_identity

string firmware_version
int32 temperature
int32 voltage
int32 error

StepperMotorCommand (Message)

uint8 cmd_type
uint8 CMD_TYPE_POSITION=1
uint8 CMD_TYPE_VELOCITY=2
uint8 CMD_TYPE_EFFORT=3
uint8 CMD_TYPE_TORQUE=4

uint8[] motors_id
int32[] params

StepperArrayMotorHardwareStatus (Message)

std_msgs/Header header
can_driver/StepperMotorHardwareStatus[] motors_hw_status