{{{#!wiki caution '''Note:''' This stack is designed for robots purchased before June 2014. For new robots, see the [[robotican|robotican]] stack. }}} <> <> == Overview == The lizi package is the main package which allows to communicate and control the Lizi robot which is made by [[http://www.robotican.net|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:= }}} 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_, 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_ 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 == {{{ #!clearsilver CS/NodeAPI node { 0{ name = lizi_node desc = This is the main lizi robot node. pub{ 0{ name= gps_pub type= sensor_msgs/NavSatFix desc= This topic publishes the GPS location of the robot. } 1{ name= imu_pub type= sensor_msgs/Imu desc= This topic publishes the orientation of the robot as measured by the internal IMU (Inertial Measurement Unit). } 2{ name= odom_pub type= nav_msgs/Odometry desc= This topic publishes the location and orientation of the robot based on the odometry computation of the wheels rotations. } 3{ name= Rangers/Left_URF type= sensor_msgs/Range desc= Left Ultrasonic Range Finder readings } 4{ name= Rangers/Rear_URF type= sensor_msgs/Range desc= Rear Ultrasonic Range Finder readings } 5{ name= Rangers/Right_URF type= sensor_msgs/Range desc= Right Ultrasonic Range Finder readings } } sub{ 0{ name= cmd_vel type= geometry_msgs/Twist desc= The robot listens to this topic and set its forward and angular velocity accordingly. } } srv{ 0{ name= set_odom type= lizi/set_odom desc= 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. } } param { 0{ name= Lizi_ID type= str default= "0" desc= The lizi id number. } 1{ name= fuse_imu_roll_pitch type= boolean default= true desc= This parameter when true uses the IMU's roll and pitch measurements. If false it assumes the robot is on a horizontal surface. } 2{ name= fuse_imu_roll_pitch type= boolean default= false desc= 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. } 3{ name= wheel_diameter type= double default= 0.14 desc= Robot wheels diameter im meters. } 4{ name= wheel_base_length type= double default= 0.275 desc= Robot width in meters. } 5{ name= encoder_cpr type= double default= 4288 for lizi4 model, 56000 for lizi2 model desc= Wheels encoders cpr = (ppr*4) } } } 1{ name = serial_node desc = 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). srv { 0{ name= reset_encoders type= std_srv/Empty desc= This service reset the encoder readings on the micro-controller counters. } 1{ name= imu_calib type= lizi/imu_calib desc= This service allows calibrating the IMU accelerometers and magnetometer. see the [[lizi_robot/Tutorials/Calibrating the Lizi robot IMU|Calibrating the Lizi robot IMU]] tutorial. } } param { 0{ name= pid_constants type= 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 desc= [kp, ki, kd, alpha(for velocity low-pass filter), control_dt (control loop interval in milliseconds)] } } pub{ 0{ name= lizi_status type= lizi/lizi_status desc= 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 } 1{ name= raw_gps type= lizi/lizi_gps desc= Internal use topic. } 2{ name= lizi_raw type= lizi/lizi_raw desc= Internal use topic. } } sub{ 0{ name= command type= lizi/lizi_command desc= 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. } 1{ name= pan_tilt type= lizi/lizi_pan_tilt desc= 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. } } } }}} == Report a Bug == <> ## AUTOGENERATED DON'T DELETE ## CategoryStack