ros0xrobot node provides ROS interface for robot bases in 0x series (pronounced as Ox). The ROS interface is supported by 0xRobotCpp library from Nex Robotics. Information from the robot base, velocity and acceleration control, is implemented via a ros0xrobot node, which publishes topics providing data received from the robot's embedded controller by 0xRobotCpp library, and sets desired velocity, acceleration and other commands in robot when new commands are received from command topics.

Installation and Getting Started

Instructions on installing ROS can be found here.

Reporting bugs and making feature requests

Bugs and requests can be reported here: <support AT nex-robotics DOT com>

ros0xrobot node

ros0xrobot

A simple node to communicate with 0x series robot from nex Robotics. Topics published by ros0xrobot node are available under topic named ros0xrobot/topic. The ros0xrobot node requires 0xRobotCpp library for establishing communication with robot base. The library is available in the '/lib' folder of source provided.

Subscribed Topics

cmd_vel (geometry_msgs/Twist)
  • Receives new velocity commands. The received velocities will be updated and maintained by robot. There is no need to send the velocity repeatedly to maintain the velocity. If the robot is kept in timeout mode, then any valid communication/command needs to be sent to the robot before timeout to keep the robot moving.

Published Topics

pose (nav_msgs/Odometry)
  • publishes odometry information (rate depends on the robot, normally 10Hz)
sonar (sensor_msgs/PointCloud)
  • publishes sonar readings. Requires enableSonar parameter to be set to true.
imu (sensor_msgs/Imu)
  • publishes imu readings. Requires enableImu parameter to be set to true.

Parameters

~port (string, default: /dev/ttyUSB0)
  • Serial port device the robot is is connected to. Set to /dev/ttyUSBx depending on port on which robot is connected.
CountsPerRev (int, default: 3840)
  • Set counts per revolution of the robot. Refer hardware manual of robot for appropriate value.
WheelDiameter (float, default: 100.0)
  • Set wheel diameter of robot in mm.
AxelLength (float, default: 290.0)
  • Set axle length in mm.
enableSonar (bool, default: false)
  • Enable or disable Sonar. This will cause the node to start publishing sonar messages when enabled.
enableImu (bool, default: false)
  • Enable or disable IMU. This will cause the node to start publishing imu messages when enabled.

Running ros0xrobot node

$rosrun ros0xrobot ros0xrobotNode

Wiki: ros0xrobot (last edited 2016-06-02 15:20:26 by nexrobotics)