repository: git://github.com/neobotix/neo_driver

This package is obsolete and will be replaced by cob_relayboard

Serial Relay Board

The Serial Relay Board does not only handle and publish error states (as a laser stop or emergency stop) or the robots state (temperature, battery volts and the battery current), it can also control can-motor-drivers and publish range measurements (ultra sonic or infra red).

For the Relay Board exist a couple of expansion boards:

  1. Gyro Board: publishes angular rates and acceleration on 3 axis.
  2. I/O Board:
  3. Radar Board: publishes velocities.

Topics to publish/subscribe and configuration parameters

Subscribed Topics

/cmd_drives (neo_msgs/DriveCmd)
  • sets joint velocities
/srb_lcd_display (neo_msgs/LCDOut)
  • sets lcd output
/srb_io_set_dig_out (neo_msgs/IOOut)
  • sets digital output
/srb_start_us_board (std_msgs/Int16)
  • starts the ultrasonic range board
/srb_stop_us_board (std_msgs/Empty)
  • stops the ultrasonic board
/srb_zero_gyro (std_msgs/Empty)
  • zeros the gyro

Published Topics

/drive_states (neo_msgs/DriveStates)
  • publishes joint states
/srb_io_dig_in (std_msgs/Int16)
  • publishes digital input
/srb_io_dig_out (std_msgs/Int16)
  • publishes digital output
/srb_io_analog_in (neo_msgs/IOAnalogIn)
  • publishes analog input
/srb_us_measurements (neo_msgs/USBoard)
  • publishes ultrasonic sensor readings
/srb_radar_measurements (neo_msgs/RadarBoard)
  • publishes radar sensor readings
/srb_gyro_measurements (neo_msgs/GyroBoard)
  • publishes gyro sensor readings
/srb_keypad (neo_msgs/Keypad)
  • publishes keypad pushbutton readings
/srb_ir_measurements (neo_msgs/IRSensors)
  • publishes infrared range sensor readings

Parameters

message_timeout (, default: 2.0)
  • sets the timeout for messages sent via serial port
requestRate (, default: 25.0)
  • sets the rate for communicating with the serial relay board
protocol_version (, default: 1)
  • sets the serial relayboard version
ComPort ()
  • sets the comport (for example /dev/ttyUSB1)
drive1/CANId ()
  • sets the canid of the first drive
drive2/CANId ()
  • sets the canid of the second drive
drive1/joint_name ()
  • sets the drives jointname
drive2/joint_name ()
  • sets the drives jointname
hasMotorRight ()
  • are motors connected to the serial relay board? [true/false]
hasMotorLeft ()
  • are motors connected to the serial relay board? [true/false]
hasIOBoard ()
  • is the io-board connected? [true/false]
hasLCDOut ()
  • is there an lcd display? [true/false]
hasUSBoard ()
  • are us-sensors connected? [true/false]
hasRadarBoard ()
  • is the radarboard connected? [true/false]
hasGyroBoard ()
  • does the gyroboard exist? [true/false]
hasKeyPad ()
  • is a keypad in use? [true/false]
hasIRSensors ()
  • are there any ir-sensors? [true/false]

Troubleshooting

I can't communicate with the Serial Relay Board, though it powers on and displays stuff on the LCD:

Make sure that your config file does not enably any non existing expansion boards/motors and that you've choose the right relayboard version and poweroff the serial relay board afterwards.

Launching relayboard.launch fails because the $ROBOT_drive*.yaml files are missing:

Set the arg "loadDrives" to "false"

Add your own Problem and Solution here

Wiki: neo_serrelayboard (last edited 2012-03-30 07:53:46 by TimoHackel)