Develop Robotics application with ROS
The Ohmni Developer Edition is built with a powerful Docker virtualization layer and ROS developers can utilize it to run the ROS framework on top of Ohmni. Beside the default ohmnilabs/ohmnidev image, we also release another docker image, tb_control, to simplify the development. The below sections will provide the basic reference guide for ROS developers to start utilizing this node.
Node | tb_control |
---|---|
Docker Version | 0.08 |
Doc Revision | 002 |
Date | June 2020 |
1. Overview
This node is a ROS software driver for Ohmnilabs robots. It provides an alternate way beside our tb-node (Nodejs driver) to control the robot actuator (e.g wheel, neck) and get sensor feedback (e.g. wheel encoder, neck position, battery voltage, docking status). Compared to tb-node, this node adds 2 more Herkulex servos to help you have more capabilities such as controlling 1 DoF camera mount. It also has built-in wheel odometry. Here are the summary features:
Feature | Control | Sense |
---|---|---|
2 Wheel actuator | PID velocity controller @50Hz | 2 wheel encoder fixed at 50Hz |
Neck servo | Herkulex position control | Position fixed at 30Hz |
2 External servo | JHerkulex position control | Position fixed at 30Hz |
Core board | None | Battery voltage Docking status. All fixed at 10Hz |
Wheel odometry | Reset position | Position, velocity fixed at 50Hz |
Note that: These sensors have fixed frequency because the communication is limited and all fit in 1 serial port with fixed baud rate 115200bps. Please contact us if you want a different feedback frequency.
2. Basic Usage
This ROS node will be packaged as the docker image that you can pull and run on top of Ohmni OS. Here are the steps to up and running.
Requirement
Ohmni Developer Edition robot
Note: For now, you need to turn off the serial port used by the tb-node, because the tb_control will also, independently, use the serial port.
If you are using any API of the tb-node (e.g. botshell API) and don’t want to turn off the tb-node, you need to change your tb-node code to turn off the serial port when using tb_control features. We will provide a seamlessly switching feature between the tb-node and the tb_control in the future release.
To turn off tb-node, adb or ssh into the bot:
In bot cli> setprop ctl.stop tb-node
Another hacky way to turn off the tb-node’s serial port without turning off the tb-node, in the below example, we use the plugin system to turn off the tb-node’s serial port for 5 seconds and then reconnect it. Within this 5 seconds period, you can use tb_control normally.
function MyPLugin(botnode) {
var self = this;
this.botnode_ = botnode;
console.log("MyPLugin loaded")
//Switch to use tb_control serial,
//by turning off the tb-node’s serial port
delete this.botnode_._serial._sport;
this.botnode_._serial._opened = false;
setTimeout(function () {
//When you want to use the tb-node’s serial port,
//turn off the tb_control or calling the disconnect service.
//Then, reconnect tb-node serial port
self.botnode_._serial.createSerial();
}, 5000);
}
module.exports = MyPLugin;
Step 1: pull the docker to your bot
In bot cli> docker pull [tb_control_docker_image]
Where [tb_control_docker_image] is: ohmnilabsvn/ohmni_ros:ohmni_ros_tbcontrol_0.0.8
Step 2: run and access the docker
In bot cli> docker run -it --network host --privileged -v /dev:/dev [tb_control_docker_image]
bash
#tb_control is running in a tmux session, you could access it by
In Docker> tmux attach -t work
Step 3: (optional) setup network, connect the bot with your local machine
Before running the docker, you could set up the network to link your bot with a local machine. So you could use other ROS debug and visualization tools in the local machine.
Firstly, make sure your local machine installed ROS. For now, we only support ROS melodic, but other versions of ROS1 should work too (e.g. kinetic, noetic). Please let us know if you have any issues when running on another version.
ROS allows multiple machines to connect to each other if:
- There must be complete, bi-directional connectivity between all pairs of machines, on all ports.
- Each machine must advertise itself by a name that all other machines can resolve.
So you must make sure your bot and the local machine are in the same local network. To check the connectivity, you could go through checking steps in this document.
Restart the docker with an additional environment variable.
In bot cli> docker run -it --network host --privileged -v /dev:/dev -e ROS_IP=[bot_ip] [tb_control_docker_image]
If connectivity is good and the docker is running, then you need to export necessary info to use any ROS tools in the local machine (e.g. rviz, rqt)
# export necessary info before running any ROS tool
In the local machine> export ROS_IP=[local_machine_ip]
In the local machine> export ROS_MASTER_URI=http://[bot_ip]:11311
TIP: if you are using Ubuntu, you can save the above command in the ~/.bashrc file to load it every time you open a new terminal.
Now you are free to access all topics/services of the tb_control
# list all available topic
In the local machine/or bot docker> rostopic list
# run visualization tool
In the local machine> rviz
3. Tutorials with CLI
3.1. Drive robot around
#setup environment
In Docker> source /opt/ros/melodic/setup.bash
#enable controller
In Docker> rosservice call /tb_control/enable_controllers "enable_controller: true
pid_velocity_motor_left: true
pid_velocity_motor_right: true"
#publish command that drives straightforward at velocity 0.1m/s
In Docker> rostopic pub -1 /tb_cmd_vel geometry_msgs/Twist "linear:
x: 0.1
y: 0.0
z: 0.0
angular:
x: 0.0
y: 0.0
z: 0.0"
#The robot should go forward for about 0.5 second before stopping. Because of the internal safety feature, you need to public the /tb_cmd_vel more than 2 Hz to get the robot to continuously move.
To have a better experience, connect your local machine with the bot and use tools like rqt_robot_steering in the local machine (set topic to /tb_cmd_vel) to manual control the bot.
#finish all step in the basic usage section
# install rqt_robot_steering if you not
In the local machine> sudo apt install ros-melodic-rqt-robot-steering
#and run
In the local machine> rosrun rqt_robot_steering rqt_robot_steering
In QT gui, set the input topic:
- /tb_cmd_vel: for pure velocity control
- /cmd_vel_accel: for velocity control with acceleration limit (see the difference if you change your speed suddenly)
😬 WARNING: watch your bot if you don’t want it to hit something. Driver safe and fun!
3.2. Get sensor stream
In this example, we will see what is the output of each sensor.
#setup environment
In Docker> source /opt/ros/melodic/setup.bash
#Examine the raw sensor through topics:
# /tb_control/servo/neck
# /tb_control/wheel_encoder
# /tb_control/tbcore_status
#
#To see the built-in wheel odom, check topic
# /tb_control/wheel_odom
#for example, try
In Docker> rostopic echo /tb_control/wheel_odom
In Docker> rostopic hz /tb_control/wheel_odom
To get a better view, connect to you local machine, then run rviz and visualize the odometry topic: /tb_control/wheel_odom (Remember to set the Global Options/Fixed Frame: /odom)
3.3. Control neck servo
We use the Herkulex servo to actuate the neck. Check this link for its user manual.
#setup environment
In Docker> source /opt/ros/melodic/setup.bash
#enable torque mode of the servo
# as the manual, the servo has 3 torque mode Break, On and Free
#Enable torque on and set the neck to the wake up position
In Docker> rosservice call /tb_control/set_servo_pos "{sid: 3, use_rad: false, pos_raw: 500, pos_rad: 0.0, torque: 1, playtime: 100}"
#move up: neck servo input raw ranges from 280-650
In Docker> rosservice call /tb_control/set_servo_pos "{sid: 3, use_rad: false, pos_raw: 650, pos_rad: 0.0, torque: 1, playtime: 100}"
#move down: neck servo input raw ranges from 280-650
In Docker> rosservice call /tb_control/set_servo_pos "{sid: 3, use_rad: false, pos_raw: 280, pos_rad: 0.0, torque: 1, playtime: 100}"
#Then, free the neck
In Docker> rosservice call /tb_control/set_servo_pos "{sid: 3, use_rad: false, pos_raw: 0, pos_rad: 0.0, torque: 2, playtime: 0}"
😬 WARNING: always free the neck or keep it in up position (i.e. to reduce the load) after using it. If you hold the neck in the torque-on mode too long and in the wake-up position, the servo might overheat and stop working.
We have not implemented the feature to limit the input voltage on the servo, like tb-node (i.e. our botshell rest_head command), so you need to be aware of the servo torque to not break the servo.
4. ROS Node
This part will list out available topics/services of the tb_control node. Note that we also brief experimental topics/services which you should only use when you clearly understand them.
4.1. Published Topics
4.1.1. /tb_control/servo/neck
Feedback position from the neck servo
Message format
Header header
#range from 0-1023
uint16 servo_pos_raw
#angle in rad, with zero pos defined by param ~servo_neck_pos_raw_zero_offset
float64 servo_pos_rad
#the last position command sent to the servo in rad
float64 servo_pos_rad_cmd (not available in this release)
#current torque mode: free-on-break (not available in this release)
uint8 torque_cmd
4.1.2. /tb_control/tbcore_status
Feedback position from the power management board
Message format
Header header
#battery cell voltage and current
uint16 voltage_cell_1
uint16 voltage_cell_2
uint16 voltage_cell_3
uint16 voltage_cell_4
uint16 voltage_cell_5
int16 charging_current
#0 if the bot is not charging 1 if it is charging
uint8 docked_status
#other system status
uint8 fet_status
uint8 status_1
uint8 status_2
uint8 status_3
uint8 status_4
4.1.3. /tb_control/wheel_encoder
Feedback position from wheel encoder
Message format
Header header
#wheel velocity in tick/50Hz
float64 motor_left_vel
float64 motor_right_vel
#wheel position from 0-2^12
int32 motor_left_pos
int32 motor_right_pos
4.1.4. /tb_control/wheel_odom
wheel odometry output
Message format: nav_msgs::Odometry
4.1.5. Experimental topics
/tb_control/servo/ext1
Feedback position from the external servo 1
/tb_control/servo/ext2
Feedback position from the external servo 2
/tb_control/robot_state
All state of the robot (not completed)
/tb_control/motor_pid_debug
Internal state of the PID velocity controller of one wheel. Need to call service /tb_control/enable_debug_pid_stream first.
4.2. Subscribed Topics
4.2.1. /tb_cmd_vel
Command linear and angular velocity to the bot. Then the bot will calculate the velocity for 2 wheels and input to a feed-forward PID velocity controller of each wheel
Message type: geometry_msgs::Twist
4.2.2. /cmd_vel_accel
Same as the above, but the controller will limit the acceleration in some level (see param \~delta_velo_raw)
Message type: geometry_msgs::Twist
4.2.3. /tb_cmd_motor_pwm
Command raw PWM to each motor. This is for if you want to design your controller instead of using ours.
Message format
Header header
#Set PWM value for each motor from -1000 to 1000
# motor_i_enable:
# true: set PWM = motor_i value
# false: set PWM = 0
bool motor_1_enable
float64 pwm_motor_1
uint16 baseoffset_1 (Obsoleted, please ignore it)
bool motor_2_enable
float64 pwm_motor_2
uint16 baseoffset_2 (Obsoleted, please ignore it)
4.2.4. /tb_cmd_servo_neck
Request command to control position of the neck servo
Message format
Header header
#send command by rad if true or by raw position if false
# (Note, use_rad is not work for this release - bug)
bool use_rad
#command in rad
float64 pos_rad
#command in raw 12 bits: 0-2^12
uint16 pos_raw
#controller playtime from current position to cmd position
# range from 1 = 11.2ms, 254 = 2.844s
# playtime shouldn’t too small (causing high acceleration and damage the servo)
uint8 playtime
4.2.5. Experimental topics:
/tb_cmd_servo_ext1
Request command to control position of the external servo 1
/tb_cmd_servo_ext2
Request command to control position of the external servo 2
/tb_cmd_motor_speed_setpoint
Request command to control position of the neck servo
4.3. Services
4.3.1. /tb_control/set_servo_pos
Set servo control mode, you should call this service first to set the servo torque mode and then using tb_cmd_servo_neck to control the servo frequently.
Service format:
#Request
# servo id is defined at params: ~servo_neck_id, ~servo_ext1_id, ~servo_ext2_id
uint8 sid
# raw position setpoint: 0-2^12
uint16 pos
#torque control mode: kBreak = 0, kOn = 1, kFree = 2
uint8 torque
#controller playtime from current position to cmd position
# range from 1 = 11.2ms, 254 = 2.844s
# playtime shouldn’t too small (causing high acceleration and damage the servo)
uint8 playtime
---
uint8 sid
4.3.2. /tb_control/connect
Connect/Disconnect to the serial bus. By default, the serial port name is defined by param ~port_name and the baud rate ~baudrate (should be fixed at 115200 for now). It is disconnected when the node starts. The robot will connect to the serial port automatically when other services need it. You should not worry about calling this manually.
Service format:
#Request
# True: connect, False: disconnect
bool connect
# serial port name
string port_name
---
#Response
bool is_connected
string port_name
4.3.3. Experimental services:
/tb_control/enable_controllers
Manually enable/disable internal PID controllers
/tb_control/enable_debug_pid_stream
Enable this node to public detail state of the PID controllers
/tb_control/enable_sensor_stream
Manually enable/disable each sensor stream (tbcore, wheel encoder, neck servo)
/tb_control/get_connect_ports
List all serial port on the bot
/tb_control/get_info
Get connection status of the serial port
/tb_control/get_pid
Get parameters of the PID controllers
/tb_control/get_servo_info
Get internal parameters of the Herkulex servo, info is print in the tb_control terminal
/tb_control/get_tbcore_status
Get info of the tbcore board
/tb_control/reset_servo_id
Set servo and motor id from original id to a new id. This service should not be used for common purposes. This only for setup new hardware
/tb_control/reset_wheel_odom
Reset the estimated position to a specific value
/tb_control/servo_write_eep
Change Herkulex servo internal register. This service should not be used for common purposes. This only for setup new hardware
/tb_control/set_pid
Set parameters for the PID controllers
/tb_control/set_servo_zero_offset
Set Herkulex servo zero offset, this is for calculating rad from raw servo position.
4.4. parameters
4.4.1. General Robot Parameter
~port_name
Default serial port name: /dev/ttyUSB0.
~baudrate
Default serial port baud rate, should be fixed at 115200 for now.
~frame_id_odom
~frame_id_baselink
Frame id name.
~enable_broadcast_transform
Broadcast transform from sensor data: like wheel odom, servo.
~wheel_radius
~wheel_separation
Robot geometry.
~max_linear_velocity
limit linear velocity of the controller. The maximum speed when no load and angular velo=0 is about 1m/s.
~max_angular_velocity
limit angular velocity of the controller.
~delta_velo_raw
For acceleration limit. value from 1(slow acceleration)-10(fast).
~motion_watchdog_enable
~motion_watchdog_period
Safety feature. If the robot wheel do not receive any motion command within motion_watchdog_period, the wheel controller will be off.
4.4.2. Herkulex servo parameter
~servo_neck_id
Servo parameter, neck id default is 3
~servo_neck_pos_raw_zero_offset
Servo parameter, to calculate neck angle in rad
~servo_neck_use_eeprom
Load servo parameters to eeprom (permanently) or to ram (temporarily)
Beside, each Herkulex servo has a list of parameters and is automatically loaded every time the serial port is connected (by using service /tb_control/connect). Please refer to Herkulex servo DRS-0101/DRS-0201 user manual for more detail.
~servo_neck_min_pos
~servo_neck_max_pos
~servo_neck_kp
~servo_neck_ki
~servo_neck_kd
~servo_neck_v_min
~servo_neck_v_max
~servo_neck_overload_pwm
~servo_neck_max_pwm
5. Talk to tb_control
You can build your ROS node to communicate with the tb_control. We provide the tb_msgs package which defines all custom messages, services and actions used in tb_control and other ROS nodes: tb_msgs repo: https://gitlab.com/ohmni-sdk/tb_ros_common/ (Please request us to grant access to that repo)
To build a custom node, first, clone and build the tb_msgs in a catkin workspace
# if you don’t have a catkin_ws, create one, then clone tb_msgs
> source /opt/ros/<your ROS distro>/setup.bash
> mkdir -p ~/catkin_ws/src
> cd ~/catkin_ws/src
> git clone [tb_msgs repo]
# Build the tb_msgs
> cd ~/catkin_ws/
> catkin_make -DCATKIN_WHITELIST_PACKAGES="tb_msgs"
#Then if you have other ROS node and want to talk to tb_control, source this workspace before building your node
your node ws> source ~/catkin_ws/devel/setup.bash
your node ws> catkin_make
6. Troubleshoot
Here we list out common issues we meet when using tb_control
6.1. Wrong serial port
usually happen when you use more than one serial port device. Check the correct serial port in /dev or /dev/usb directory. Then change the ~port_name and restart the bot; or using service /tb_control/connect
6.2. The serial port is not received any data
Make sure no process opens the serial port. For example tb-node. Another case is that our RJ45 connector is not designed for hot-plugging. So do not hot-plug any device in the RJ45 port, it might easily damage the serial port RX/TX pin
6.3. The neck is not move for the first time using tb_control
The Herkulex servo parameter is not loaded properly. For checking, use the service /tb_control/get_servo_info for the id 3 to get parameters of the neck servo and compare it with the servo parameter from the ROS parameter server. If these parameters are not the same, then we will need to re-load it to eeprom. First set ~servo_neck_use_eeprom to true, using /tb_control/connect to connect to the serial port (the parameters will be loaded to the servo automatically)
6.4. The robot and the local machine is not connected
Re-check the step 3 above, and refer to the ROS network document to see if your local machine and the robot are connected.
6.5. Neck does not move with /tb_control/set_servo_pos
Wait for the next update.
7. Revision History
Date | Version | Note |
---|---|---|
June 2020 | 001 | Initial and Beta release |
July 2020 | 002 | Simplify network setup |
Comments
0 comments
Article is closed for comments.