Note: This stack is designed for robots purchased before June 2014. For new robots, see the robotican stack.

Only released in EOL distros:  

lizi_robot: lizi | lizi_arduino | lizi_base_station | lizi_urdf

Package Summary

The main Lizi robot package

Overview

The lizi package is the main package which allows to communicate and control the Lizi robot which is made by RoboTiCan.

Usage

Users can run the main launch file: lizi.launch to initiate all the Lizi robot controllers and sensors with a single command.

$ roslaunch lizi lizi.launch id:=<ID>

For example, running the launch file with lizi id value of 1:

$ roslaunch lizi lizi.launch id:=1

This command should be executed on the lizi robot computer. For remote operation see the lizi_base_station package. The id number sets the robot name to be lizi_<ID>, this is extremely important when working with several Lizi robot as a group of robots. This allows giving each robot in the group a unique name. The id argument can be any desired id number. The id number affect the namespace and the robot description file links and joint names. All the topics, services and parameters will have a lizi_<ID> prefix. The lizi.launch can also be used to load nodes for the front webcam, the Asus RGB-D camera and the Hokuyo laser scanner.

The lizi.launch file also loads the configuration file: lizi_robot/lizi/config/default.yaml file which contains various parameters.

Nodes

lizi_node

This is the main lizi robot node.

Subscribed Topics

cmd_vel (geometry_msgs/Twist)
  • The robot listens to this topic and set its forward and angular velocity accordingly.

Published Topics

gps_pub (sensor_msgs/NavSatFix)
  • This topic publishes the GPS location of the robot.
imu_pub (sensor_msgs/Imu)
  • This topic publishes the orientation of the robot as measured by the internal IMU (Inertial Measurement Unit).
odom_pub (nav_msgs/Odometry)
  • This topic publishes the location and orientation of the robot based on the odometry computation of the wheels rotations.
Rangers/Left_URF (sensor_msgs/Range)
  • Left Ultrasonic Range Finder readings
Rangers/Rear_URF (sensor_msgs/Range)
  • Rear Ultrasonic Range Finder readings
Rangers/Right_URF (sensor_msgs/Range)
  • Right Ultrasonic Range Finder readings

Services

set_odom (lizi/set_odom)
  • This service set the odometry of the robot to any desired location and orientation, it should receive three fields: float32 x, float32 y, float32 theta.

Parameters

Lizi_ID (str, default: "0")
  • The lizi id number.
fuse_imu_roll_pitch (boolean, default: true)
  • This parameter when true uses the IMU's roll and pitch measurements. If false it assumes the robot is on a horizontal surface.
fuse_imu_roll_pitch (boolean, default: false)
  • This parameter when true uses the IMU's yaw measurement instead of the calculated odometry heading. If false uses the robot odometry to determine its heading.
wheel_diameter (double, default: 0.14)
  • Robot wheels diameter im meters.
wheel_base_length (double, default: 0.275)
  • Robot width in meters.
encoder_cpr (double, default: 4288 for lizi4 model, 56000 for lizi2 model)
  • Wheels encoders cpr = (ppr*4)

serial_node

This is an internal node that is responsible for the communication between the internal Micro Controller and the computer. This node belongs to the rosserial_python package(http://wiki.ros.org/rosserial).

Subscribed Topics

command (lizi/lizi_command)
  • Instead of using the cmd_vel topic, one may want to directly command the robot motors. The lizi/lizi_command message contains two fields: int32 left_wheel, int32 right_wheel . The values are in encoder ticks per second units.
pan_tilt (lizi/lizi_pan_tilt)
  • This topic sends command to the pan tilt system that orients the RGB-D sensor. The lizi_pan_tilt message contains two fields: float32 pan_angle and float32 tilt_angle. The values are in radians units. Note that the positive directions of the pan-tilt are left and up respectively. A single message is enough to set the required angles (no need for publishing these messages continuously). The pan angle range of motion is -35 to +35, and the tilt range is -30 to +30. These limitations are constrained by software.

Published Topics

lizi_status (lizi/lizi_status)
  • This topic publishes the battery voltage (battery_volts field) in Volts and the faults (faults fiels) report. The voltage should be in the range of 11V to 14V. The faults parameter is constructed from 4 bits as follows: Bit 0 is set if motors driver has faults. Bit 1 is set if motors torque is off. Bit 2 is set if GPS location is not valid. Bit 3 is set if IMU readings are not valid. faults = (Bit 0)*1 + (Bit 1)*2 + (Bit 2)*4 + (Bit 3)*8
raw_gps (lizi/lizi_gps)
  • Internal use topic.
lizi_raw (lizi/lizi_raw)
  • Internal use topic.

Services

reset_encoders (std_srv/Empty)
  • This service reset the encoder readings on the micro-controller counters.
imu_calib (lizi/imu_calib)

Parameters

pid_constants (float array, default: [0.02,0.2,0.0,0.5,1.0] for lizi4, [0.001,0.01, 0.0, 0.5,1.0] for lizi2)
  • [kp, ki, kd, alpha(for velocity low-pass filter), control_dt (control loop interval in milliseconds)]

Report a Bug

Use GitHub to report bugs or submit feature requests. [View active issues]

Wiki: lizi (last edited 2016-07-06 06:00:52 by yamgeva)